Skip to content

Commit 76228bd

Browse files
committed
will prefix tf_prefix to imagemsg and camerainfo regular frame_id upon request in launch file
1 parent d1b34eb commit 76228bd

File tree

6 files changed

+35
-9
lines changed

6 files changed

+35
-9
lines changed

include/spinnaker_sdk_camera_driver/capture.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,7 @@ namespace acquisition {
104104
float exposure_time_;
105105
double target_grey_value_;
106106
// int decimation_;
107-
107+
string tf_prefix_;
108108
int soft_framerate_; // Software (ROS) frame rate
109109

110110
int MASTER_CAM_;
@@ -128,7 +128,7 @@ namespace acquisition {
128128
// grid view related variables
129129
bool GRID_CREATED_;
130130
Mat grid_;
131-
131+
132132
// ros variables
133133
ros::NodeHandle nh_;
134134
ros::NodeHandle nh_pvt_;

launch/acquisition.launch

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,13 @@
2121
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
2222
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
2323

24-
<!-- nodelet params-->
24+
<!-- nodelet manager params-->
2525
<arg name="nodelet_manager_name" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
2626
<arg name="start_nodelet_manager" default="true" doc="If set to True(default), creates a nodelet manager with $(arg nodelet_manager_name).
2727
If False, the acquisition/capture_nodelet waits for the nodelet_manager name $(arg nodelet_manager_name)" />
2828

29+
<!-- Capture nodelet params-->
30+
<arg name="tf_prefix" default="" />
2931
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
3032
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" if="$(arg start_nodelet_manager)" />
3133

@@ -51,8 +53,9 @@
5153
<param name="time" value="$(arg time)" />
5254
<param name="utstamps" value="$(arg utstamps)" />
5355
<param name="to_ros" value="$(arg to_ros)"/>
54-
<param name="max_rate_save" value="$(arg max_rate_save)"/>
55-
56+
<param name="max_rate_save" value="$(arg max_rate_save)" />
57+
<param name="tf_prefix" value="$(arg tf_prefix)" />
58+
5659
</node>
5760

5861
</launch>

launch/acquisition_node.launch

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,11 @@
2121
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
2222
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
2323
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
24-
24+
25+
<!-- acquisiton node params-->
26+
<arg name="tf_prefix" default="" />
2527
<!-- load the acquisition node -->
28+
2629
<node pkg="spinnaker_sdk_camera_driver" type="acquisition_node" name="acquisition_node" output="$(arg output)" args="" respawn="false" >
2730

2831
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
@@ -45,6 +48,7 @@
4548
<param name="utstamps" value="$(arg utstamps)" />
4649
<param name="to_ros" value="$(arg to_ros)"/>
4750
<param name="max_rate_save" value="$(arg max_rate_save)"/>
51+
<param name="tf_prefix" value="$(arg tf_prefix)" />
4852

4953
</node>
5054

launch/multiple_nodelet_example.launch

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<!-- args namespacing -->
33
<arg name="robot_ns" default="$(env ROBOT_NAME)" />
44
<arg name="vision_nm" default="vision_nodelet_manager_uas" doc="name of the nodelet manager" />
5+
<arg name="camera_tf_prefix" default="" />
6+
57

68
<group ns="$(arg robot_ns)">
79
<!-- launch nodelet manager -->
@@ -10,6 +12,7 @@
1012
<include file="$(find spinnaker_sdk_camera_driver)/launch/acquisition.launch" >
1113
<arg name="nodelet_manager_name" value="$(arg vision_nm)" />
1214
<arg name="start_nodelet_manager" value="false" />
15+
<arg name="tf_prefix" value="$(arg camera_tf_prefix)" />
1316
</include>
1417

1518
<!-- launch apriltag_ros nodelet -->

launch/nodelet_subscriber_example.launch

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,14 +21,15 @@
2121
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
2222
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
2323

24-
<!-- nodelet params-->
24+
<!-- nodelet manager params-->
2525
<arg name="nodelet_manager_name" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
2626
<arg name="start_nodelet_manager" default="false" doc="If set to True, creates a nodelet manager with $(arg nodelet_manager_name).
2727
If False, the acquisition/capture_nodelet waits for the nodelet_manager name $(arg nodelet_manager_name)" />
2828

29+
<!-- Capture nodelet params-->
30+
<arg name="tf_prefix" default="" />
2931

3032
<!-- start the nodelet manager -->
31-
3233
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" />
3334

3435
<!-- load the acquisition nodelet -->
@@ -54,6 +55,7 @@
5455
<param name="utstamps" value="$(arg utstamps)" />
5556
<param name="to_ros" value="$(arg to_ros)"/>
5657
<param name="max_rate_save" value="$(arg max_rate_save)"/>
58+
<param name="tf_prefix" value="$(arg tf_prefix)" />
5759

5860
</node>
5961

src/capture.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -478,6 +478,15 @@ void acquisition::Capture::read_parameters() {
478478
}else ROS_INFO(" Frames will be recorded until user termination");
479479
}else ROS_WARN(" 'frames' Parameter not set, using defult behavior, frames will be recorded until user termination");
480480
}
481+
482+
if (nh_pvt_.hasParam("tf_prefix")){
483+
nh_pvt_.param<std::string>("tf_prefix", tf_prefix_, "");
484+
ROS_INFO_STREAM(" tf_prefix set to: "<<tf_prefix_);
485+
}
486+
else ROS_WARN(" 'tf_prefix' Parameter not set, using default behavior tf_prefix=" " ");
487+
488+
489+
481490

482491
bool intrinsics_list_provided = false;
483492
XmlRpc::XmlRpcValue intrinsics_list;
@@ -766,9 +775,13 @@ void acquisition::Capture::export_to_ROS() {
766775
double t = ros::Time::now().toSec();
767776
std_msgs::Header img_msg_header;
768777
img_msg_header.stamp = mesg.header.stamp;
778+
string frame_id_prefix;
779+
if (tf_prefix_.compare("") != 0)
780+
frame_id_prefix = tf_prefix_ +"/";
781+
else frame_id_prefix="";
769782

770783
for (unsigned int i = 0; i < numCameras_; i++) {
771-
img_msg_header.frame_id = "cam_"+to_string(i)+"_optical_frame";
784+
img_msg_header.frame_id = frame_id_prefix + "cam_"+to_string(i)+"_optical_frame";
772785

773786
if(color_)
774787
img_msgs[i]=cv_bridge::CvImage(img_msg_header, "bgr8", frames_[i]).toImageMsg();
@@ -777,6 +790,7 @@ void acquisition::Capture::export_to_ROS() {
777790

778791
if (PUBLISH_CAM_INFO_){
779792
cam_info_msgs[i]->header.stamp = mesg.header.stamp;
793+
cam_info_msgs[i]->header.frame_id = frame_id_prefix + "cam_"+to_string(i)+"_optical_frame";
780794
}
781795
camera_image_pubs[i].publish(img_msgs[i],cam_info_msgs[i]);
782796
/*

0 commit comments

Comments
 (0)