Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/namespacing launch fixes #36

Open
wants to merge 4 commits into
base: kinetic
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -143,10 +143,6 @@ install(DIRECTORY include
## Mark other files for installation (e.g. launch and bag files, etc.)
install(FILES
plugins.xml
launch/mono_camera.launch
launch/mono_camera_nodelet.launch
launch/stereo_camera_one_node.launch
launch/stereo_camera_two_nodes.launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

Expand Down
2 changes: 1 addition & 1 deletion cfg/AvtVimbaCameraStereo.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ gen.add("right_frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING
gen.add("right_trig_timestamp_topic", str_t, SensorLevels.RECONFIGURE_STOP, "Sets the topic from which an externally trigged camera receives its trigger timestamps.", "")
# ACQUISITION
gen.add("right_acquisition_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Camera acquisition mode", "Continuous", edit_method = acquisition_mode_enum)
gen.add("right_acquisition_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the expected triggering rate in externally triggered mode.", 2.0, 1.0, 30.0)
gen.add("right_acquisition_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the expected triggering rate in externally triggered mode.", 10.0, 1.0, 30.0)
# TRIGGER
gen.add("right_trigger_source", str_t, SensorLevels.RECONFIGURE_STOP, "Camera trigger source", "FixedRate", edit_method = trigger_source_enum)
gen.add("right_trigger_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Camera trigger mode", "On", edit_method = trigger_mode_enum)
Expand Down
2 changes: 1 addition & 1 deletion include/avt_vimba_camera/mono_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class MonoCamera {
// Dynamic reconfigure
typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
ReconfigureServer reconfigure_server_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

// Camera configuration
Config camera_config_;
Expand Down
2 changes: 1 addition & 1 deletion include/avt_vimba_camera/stereo_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ class StereoCamera {
typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
typedef avt_vimba_camera::AvtVimbaCameraStereoConfig StereoConfig;
typedef dynamic_reconfigure::Server<StereoConfig> ReconfigureServer;
ReconfigureServer reconfigure_server_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

// Camera configuration
StereoConfig camera_config_;
Expand Down
3 changes: 2 additions & 1 deletion launch/mono_camera.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
<launch>
<arg name="guid" default="50-0503343290"/>

<group ns="camera">
<node name="image_proc" pkg="image_proc" type="image_proc"/>
</group>

<node name="camera" pkg="avt_vimba_camera" type="mono_camera_node" output="screen">
<param name="guid" value="50-0503343290"/>
<param name="guid" value="$(arg guid)"/>
<param name="ip" value=""/>
<param name="camera_info_url" value="file://$(find avt_vimba_camera)/calibrations/calibration_50-0503343290.yaml"/>
<param name="frame_id" value="left_optical"/>
Expand Down
12 changes: 7 additions & 5 deletions launch/stereo_camera_one_node.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,22 @@
<arg name="stereo" default="stereo"/>
<arg name="left_guid" default="50-0503343289"/>
<arg name="right_guid" default="50-0503343290"/>

<node ns="$(arg stereo)" name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc" output="screen"/>
<arg name="left_camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg left_guid).yaml"/>
<arg name="right_camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg right_guid).yaml"/>


<node ns="$(arg stereo)" name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc" output="screen"/>

<node name="$(arg stereo)" pkg="avt_vimba_camera" type="stereo_camera_node" output="screen">

<!-- Static params -->
<param name="left_guid" value="$(arg left_guid)"/>
<param name="right_guid" value="$(arg right_guid)"/>
<param name="left_camera_info_url" value="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg left_guid).yaml"/>
<param name="right_camera_info_url" value="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg right_guid).yaml"/>
<param name="left_camera_info_url" value="$(arg left_camera_info_url)"/>
<param name="right_camera_info_url" value="$(arg right_camera_info_url)"/>

<param name="show_debug_prints" value="false"/>
<!--rosparam command="load" file="$(find avt_vimba_camera)/params.yaml"/-->
</node>

</launch>

14 changes: 9 additions & 5 deletions launch/stereo_camera_two_nodes.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
<launch>

<arg name="left_guid" default="50-0503343289"/>
<arg name="right_guid" default="50-0503343290"/>
<arg name="left_camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg left_guid).yaml"/>
<arg name="right_camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_$(arg right_guid).yaml"/>

<group ns="stereo">
<node name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc"/>

Expand All @@ -13,9 +18,9 @@


<node name="left" pkg="avt_vimba_camera" type="mono_camera_node" output="screen">
<param name="guid" value="50-0503343289"/>
<param name="guid" value="$(arg left_guid)"/>
<param name="ip_address" value=""/>
<param name="camera_info_url" value="file://$(find avt_vimba_camera)/calibrations/calibration_50-0503343289.yaml"/>
<param name="camera_info_url" value="$(arg left_camera_info_url)"/>
<param name="frame_id" value="left_optical"/>
<param name="trig_timestamp_topic" value=""/>
<param name="trigger_source" value="FixedRate"/>
Expand All @@ -37,9 +42,9 @@
</node>

<node name="right" pkg="avt_vimba_camera" type="mono_camera_node" output="screen">
<param name="guid" value="50-0503343290"/>
<param name="guid" value="$(arg right_guid)"/>
<param name="ip_address" value=""/>
<param name="camera_info_url" value="file://$(find avt_vimba_camera)/calibrations/calibration_50-0503343290.yaml"/>
<param name="camera_info_url" value="$(arg right_camera_info_url)"/>
<param name="frame_id" value="right_optical"/>
<param name="trig_timestamp_topic" value=""/>
<param name="trigger_source" value="Line1"/>
Expand All @@ -60,4 +65,3 @@
</node>
</group>
</launch>

8 changes: 5 additions & 3 deletions src/mono_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

namespace avt_vimba_camera {

MonoCamera::MonoCamera(ros::NodeHandle& nh, ros::NodeHandle& nhp) : nh_(nh), nhp_(nhp), it_(nhp), cam_(ros::this_node::getName()) {
MonoCamera::MonoCamera(ros::NodeHandle& nh, ros::NodeHandle& nhp) : nh_(nh), nhp_(nhp), it_(nh), cam_(ros::this_node::getName()) {
// Prepare node handle for the camera
// TODO use nodelets with getMTNodeHandle()

Expand All @@ -60,8 +60,10 @@ MonoCamera::MonoCamera(ros::NodeHandle& nh, ros::NodeHandle& nhp) : nh_(nh), nhp
// Set camera info manager
info_man_ = boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(nhp_, frame_id, camera_info_url_));

// Start dynamic_reconfigure & run configure()
reconfigure_server_.setCallback(boost::bind(&avt_vimba_camera::MonoCamera::configure, this, _1, _2));
// Start up the dynamic_reconfigure service, note that this needs to stick around after this function ends
reconfigure_server_ = boost::make_shared <ReconfigureServer>(nhp_);
ReconfigureServer::CallbackType f = boost::bind(&avt_vimba_camera::MonoCamera::configure, this, _1, _2);
reconfigure_server_->setCallback(f);
}

MonoCamera::~MonoCamera(void) {
Expand Down
18 changes: 10 additions & 8 deletions src/stereo_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,8 @@ void StereoCamera::run() {
api_.start();

// Set the image publishers before the streaming
left_pub_ = it_.advertiseCamera("/stereo_down/left/image_raw", 1);
right_pub_ = it_.advertiseCamera("/stereo_down/right/image_raw", 1);
left_pub_ = it_.advertiseCamera("left/image_raw", 1);
right_pub_ = it_.advertiseCamera("right/image_raw", 1);

// Set the frame callbacks
left_cam_.setCallback(boost::bind(&avt_vimba_camera::StereoCamera::leftFrameCallback, this, _1));
Expand All @@ -83,14 +83,16 @@ void StereoCamera::run() {
updater_.update();

// Set camera info managers
left_info_man_ = boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(ros::NodeHandle(nhp_, "left"),"left_optical",left_camera_info_url_));
right_info_man_ = boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(ros::NodeHandle(nhp_, "right"),"right_optical",right_camera_info_url_));
left_info_man_ = boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh_, "left"),"left_optical",left_camera_info_url_));
right_info_man_ = boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh_, "right"),"right_optical",right_camera_info_url_));

pub_left_temp_ = nhp_.advertise<std_msgs::Float64>("left_temp", 1, true);
pub_right_temp_ = nhp_.advertise<std_msgs::Float64>("right_temp", 1, true);
pub_left_temp_ = nh_.advertise<std_msgs::Float64>("left/temp", 1, true);
pub_right_temp_ = nh_.advertise<std_msgs::Float64>("right/temp", 1, true);

// Start dynamic_reconfigure & run configure()
reconfigure_server_.setCallback(boost::bind(&StereoCamera::configure, this, _1, _2));
// Start up the dynamic_reconfigure service, note that this needs to stick around after this function ends
reconfigure_server_ = boost::make_shared <ReconfigureServer>(nhp_);
ReconfigureServer::CallbackType f = boost::bind(&StereoCamera::configure, this, _1, _2);
reconfigure_server_->setCallback(f);

}

Expand Down