Skip to content

Commit

Permalink
Enable configuration of the TF publication rate when using tf_dynamic
Browse files Browse the repository at this point in the history
The parameter is called tf_publication_rate
  • Loading branch information
severin-lemaignan authored and skadge committed Mar 24, 2017
1 parent 751e252 commit c00eb84
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 29 deletions.
1 change: 1 addition & 0 deletions realsense_camera/include/realsense_camera/base_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ class BaseNodelet: public nodelet::Nodelet
bool enable_pointcloud_;
bool enable_tf_;
bool enable_tf_dynamic_;
double tf_publication_rate_;
const uint16_t *image_depth16_;
cv::Mat cvWrapper_;
std::mutex frame_mutex_[STREAM_COUNT];
Expand Down
1 change: 1 addition & 0 deletions realsense_camera/include/realsense_camera/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ namespace realsense_camera
const bool ENABLE_PC = false;
const bool ENABLE_TF = true;
const bool ENABLE_TF_DYNAMIC = false;
const double TF_PUBLICATION_RATE = 1.0;
const std::string DEFAULT_MODE = "preset";
const std::string DEFAULT_BASE_FRAME_ID = "camera_link";
const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame";
Expand Down
58 changes: 30 additions & 28 deletions realsense_camera/launch/r200_nodelet_modify_params.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,35 +8,37 @@

<!-- These 'arg' tags are just place-holders for passing values from test files.
The recommended way is to pass the values directly into the 'param' tags. -->
<arg name="enable_depth" default="true" />
<arg name="enable_ir" default="false" />
<arg name="enable_ir2" default="false" />
<arg name="enable_color" default="true" />
<arg name="enable_pointcloud" default="false" />
<arg name="enable_tf" default="true" />
<arg name="enable_tf_dynamic" default="false" />
<arg name="mode" default="manual" />
<arg name="depth_width" default="640" />
<arg name="depth_height" default="480" />
<arg name="color_width" default="1920" />
<arg name="color_height" default="1080" />
<arg name="depth_fps" default="30" />
<arg name="color_fps" default="30" />
<arg name="enable_depth" default="true" />
<arg name="enable_ir" default="false" />
<arg name="enable_ir2" default="false" />
<arg name="enable_color" default="true" />
<arg name="enable_pointcloud" default="false" />
<arg name="enable_tf" default="true" />
<arg name="enable_tf_dynamic" default="false" />
<arg name="tf_publication_rate" default="1.0" />
<arg name="mode" default="manual" />
<arg name="depth_width" default="640" />
<arg name="depth_height" default="480" />
<arg name="color_width" default="1920" />
<arg name="color_height" default="1080" />
<arg name="depth_fps" default="30" />
<arg name="color_fps" default="30" />

<param name="$(arg camera)/driver/enable_depth" type="bool" value="$(arg enable_depth)" />
<param name="$(arg camera)/driver/enable_ir" type="bool" value="$(arg enable_ir)" />
<param name="$(arg camera)/driver/enable_ir2" type="bool" value="$(arg enable_ir2)" />
<param name="$(arg camera)/driver/enable_color" type="bool" value="$(arg enable_color)" />
<param name="$(arg camera)/driver/enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="$(arg camera)/driver/enable_tf" type="bool" value="$(arg enable_tf)" />
<param name="$(arg camera)/driver/enable_tf_dynamic" type="bool" value="$(arg enable_tf_dynamic)" />
<param name="$(arg camera)/driver/mode" type="str" value="$(arg mode)" />
<param name="$(arg camera)/driver/depth_width" type="int" value="$(arg depth_width)" />
<param name="$(arg camera)/driver/depth_height" type="int" value="$(arg depth_height)" />
<param name="$(arg camera)/driver/color_width" type="int" value="$(arg color_width)" />
<param name="$(arg camera)/driver/color_height" type="int" value="$(arg color_height)" />
<param name="$(arg camera)/driver/depth_fps" type="int" value="$(arg depth_fps)" />
<param name="$(arg camera)/driver/color_fps" type="int" value="$(arg color_fps)" />
<param name="$(arg camera)/driver/enable_depth" type="bool" value="$(arg enable_depth)" />
<param name="$(arg camera)/driver/enable_ir" type="bool" value="$(arg enable_ir)" />
<param name="$(arg camera)/driver/enable_ir2" type="bool" value="$(arg enable_ir2)" />
<param name="$(arg camera)/driver/enable_color" type="bool" value="$(arg enable_color)" />
<param name="$(arg camera)/driver/enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="$(arg camera)/driver/enable_tf" type="bool" value="$(arg enable_tf)" />
<param name="$(arg camera)/driver/enable_tf_dynamic" type="bool" value="$(arg enable_tf_dynamic)" />
<param name="$(arg camera)/driver/tf_publication_rate" type="double" value="$(arg tf_publication_rate)" />
<param name="$(arg camera)/driver/mode" type="str" value="$(arg mode)" />
<param name="$(arg camera)/driver/depth_width" type="int" value="$(arg depth_width)" />
<param name="$(arg camera)/driver/depth_height" type="int" value="$(arg depth_height)" />
<param name="$(arg camera)/driver/color_width" type="int" value="$(arg color_width)" />
<param name="$(arg camera)/driver/color_height" type="int" value="$(arg color_height)" />
<param name="$(arg camera)/driver/depth_fps" type="int" value="$(arg depth_fps)" />
<param name="$(arg camera)/driver/color_fps" type="int" value="$(arg color_fps)" />
<!-- Refer to the Wiki http://wiki.ros.org/realsense_camera for list of supported parameters -->

<group ns="$(arg camera)">
Expand Down
3 changes: 2 additions & 1 deletion realsense_camera/src/base_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ namespace realsense_camera
pnh_.param("enable_pointcloud", enable_pointcloud_, ENABLE_PC);
pnh_.param("enable_tf", enable_tf_, ENABLE_TF);
pnh_.param("enable_tf_dynamic", enable_tf_dynamic_, ENABLE_TF_DYNAMIC);
pnh_.param("tf_publication_rate", tf_publication_rate_, TF_PUBLICATION_RATE);
pnh_.param("depth_width", width_[RS_STREAM_DEPTH], DEPTH_WIDTH);
pnh_.param("depth_height", height_[RS_STREAM_DEPTH], DEPTH_HEIGHT);
pnh_.param("color_width", width_[RS_STREAM_COLOR], COLOR_WIDTH);
Expand Down Expand Up @@ -1210,7 +1211,7 @@ namespace realsense_camera
// Publish transforms for the cameras
ROS_INFO_STREAM(nodelet_name_ << " - Publishing camera transforms (/tf)");

ros::Rate loop_rate(1);
ros::Rate loop_rate(tf_publication_rate_);

while (ros::ok())
{
Expand Down

0 comments on commit c00eb84

Please sign in to comment.