ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Is stereo_nodelet
exist? If not, you have two choices: you create a nodelet manager for the two nodelets or create them as standalone nodelets:
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
<!-- Generate a point cloud from the disparity image -->
<node pkg="nodelet" type="nodelet" name="disparity2cloud" args="load rtabmap_ros/point_cloud_xyz nodelet_manager">
<remap from="disparity/image" to="$(arg camera)/disparity"/>
<remap from="disparity/camera_info" to="$(arg camera)/right/camera_info"/>
<remap from="cloud" to="cloudXYZ"/>
<param name="voxel_size" type="double" value="0.05"/>
<param name="decimation" type="int" value="4"/>
<param name="max_depth" type="double" value="10"/>
</node>
<!-- Create point cloud for the local planner -->
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection nodelet_manager">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/planner/planner_cloud"/>
<param name="frame_id" type="string" value="artemisBody"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.0"/>
</node>
or
<!-- Generate a point cloud from the disparity image -->
<node pkg="nodelet" type="nodelet" name="disparity2cloud" args="standalone rtabmap_ros/point_cloud_xyz">
<remap from="disparity/image" to="$(arg camera)/disparity"/>
<remap from="disparity/camera_info" to="$(arg camera)/right/camera_info"/>
<remap from="cloud" to="cloudXYZ"/>
<param name="voxel_size" type="double" value="0.05"/>
<param name="decimation" type="int" value="4"/>
<param name="max_depth" type="double" value="10"/>
</node>
<!-- Create point cloud for the local planner -->
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="standalone rtabmap_ros/obstacles_detection">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/planner/planner_cloud"/>
<param name="frame_id" type="string" value="artemisBody"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.0"/>
</node>
Well, the first choice is preferred if cloudXYZ is used only by obstacles_detection nodelet (to keep transferred messages in memory).
2 | No.2 Revision |
Is stereo_nodelet
exist? If not, you have two choices: you create a nodelet manager for the two nodelets or create them as standalone nodelets:
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
<!-- Generate a point cloud from the disparity image -->
<node pkg="nodelet" type="nodelet" name="disparity2cloud" args="load rtabmap_ros/point_cloud_xyz nodelet_manager">
<remap from="disparity/image" to="$(arg camera)/disparity"/>
<remap from="disparity/camera_info" to="$(arg camera)/right/camera_info"/>
<remap from="cloud" to="cloudXYZ"/>
<param name="voxel_size" type="double" value="0.05"/>
<param name="decimation" type="int" value="4"/>
<param name="max_depth" type="double" value="10"/>
</node>
<!-- Create point cloud for the local planner -->
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection nodelet_manager">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/planner/planner_cloud"/>
<param name="frame_id" type="string" value="artemisBody"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.0"/>
</node>
or
<!-- Generate a point cloud from the disparity image -->
<node pkg="nodelet" type="nodelet" name="disparity2cloud" args="standalone rtabmap_ros/point_cloud_xyz">
<remap from="disparity/image" to="$(arg camera)/disparity"/>
<remap from="disparity/camera_info" to="$(arg camera)/right/camera_info"/>
<remap from="cloud" to="cloudXYZ"/>
<param name="voxel_size" type="double" value="0.05"/>
<param name="decimation" type="int" value="4"/>
<param name="max_depth" type="double" value="10"/>
</node>
<!-- Create point cloud for the local planner -->
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="standalone rtabmap_ros/obstacles_detection">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/planner/planner_cloud"/>
<param name="frame_id" type="string" value="artemisBody"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.0"/>
</node>
Well, the first choice is preferred if cloudXYZ is used only by obstacles_detection nodelet (to keep transferred messages in memory).
EDIT Beware that the nodelets are in "/stereo_camera" namespace. If you want to remap disparity/image to artemis/navCam/disparity, make sure you set your argument "camera=/artemis/navCam" with leading slash. Otherwise, it may try to subscribe to "/stereo_camera/artemis/navCam/disparity".