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

[jsk_robot_startup] Add launch files for rtabmap #639

Merged
merged 2 commits into from
Jul 28, 2016
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
<arg name="slam_laser_max_height" default="0.2"/>
<arg name="slam_laser_min_height" default="-0.2"/>
<arg name="parameter_yaml" default="$(find jsk_robot_startup)/config/default_odometry_params.yaml"/>
<arg name="use_gmapping" default="true"/>
<arg name="use_rtabmap" default="false"/>

<!-- Add slam laser pointcloud nodes to multisense_laser nodelet -->
<include file="$(find jsk_robot_startup)/launch/slam_laser_nodelets.launch" if="$(arg set_slam_laser_params)">
Expand Down Expand Up @@ -39,7 +41,7 @@
<arg name="use_slam_feedback" value="$(arg use_slam_feedback)"/>
</include>

<include file="$(find jsk_robot_startup)/launch/gmapping.launch">
<include file="$(find jsk_robot_startup)/launch/gmapping.launch" if="$(arg use_gmapping)">
<arg name="cloud_in" value="/slam_distance_filtered_laser_snapshots/output_cloud" />
<arg name="odom_frame" value="biped_odom_particle" if="$(arg use_particle_odom)"/> <!-- map->biped_odom_particle->odom_init -->
<arg name="odom_frame" value="odom_init" unless="$(arg use_particle_odom)"/> <!-- map->odom_init -->
Expand All @@ -57,6 +59,21 @@
<arg name="stt" value="0.025" />
</include>

<include file="$(find jsk_robot_startup)/launch/rtabmap.launch" if="$(arg use_rtabmap)">
<arg name="use_rviz" default="false" />
<arg name="use_stereo_odometry" default="false" />
<arg name="use_rtabmap" default="true" />
<arg name="odom_topic" default="/biped_odom_particle" /> <!-- only used when use_stereo_odometry is false -->
<arg name="base_frame_id" default="BODY" />
<arg name="odom_frame_id" default="biped_odom_particle" />
<arg name="map_frame_id" default="map" />
<arg name="publish_tf" default="true" />
<arg name="left_image" default="/multisense_local/left/image_rect"/>
<arg name="right_image" default="/multisense_local/right/image_rect"/>
<arg name="left_camera_info" default="/multisense_local/left/camera_info"/>
<arg name="right_camera_info" default="/multisense_local/right/camera_info"/>
</include>

<node pkg="jsk_robot_startup" type="OdometryTfManager.py" name="odom_tf_manager">
<param name="~map_frame" value="map"/>
<param name="~particle_frame" value="biped_odom_particle"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,8 @@
<arg name="slam_laser_max_height" value="0.5"/>
<arg name="slam_laser_min_height" value="-0.5"/>
<arg name="parameter_yaml" default="$(arg ODOMETRY_PARAM)"/>
<arg name="use_gmapping" value="true"/>
<arg name="use_rtabmap" value="false"/>
</include>

<include file="$(find jsk_footstep_planner)/launch/heightmap_perception/heightmap.launch">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<arg name="use_slam_feedback" default="false"/>
<arg name="use_odometry_iir_filter" default="false"/>
<arg name="parameter_yaml" default="$(find jsk_robot_startup)/config/default_odometry_params.yaml"/>
<arg name="map_topic" default="/map"/>

<!-- robot dependent parameters -->
<rosparam command="load" file="$(arg parameter_yaml)"/>
Expand Down Expand Up @@ -114,7 +115,7 @@
<node pkg="jsk_robot_startup" type="SlamMapTfToOdometry.py" name="slam_map_to_odometry"
output="screen">
<remap from="~output" to="/slam_odom" />
<remap from="~map" to="/map" />
<remap from="~map" to="$(arg map_topic)" />
<remap from="~base_odom" to="/biped_odom_particle" />
<rosparam>
rate: 10
Expand Down
105 changes: 105 additions & 0 deletions jsk_robot_common/jsk_robot_startup/launch/rtabmap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
<launch>
<arg name="use_rviz" default="false" />
<arg name="use_stereo_odometry" default="true" />
<arg name="use_rtabmap" default="true" />
<arg name="odom_topic" default="/odom" /> <!-- only used when use_stereo_odometry is false -->

<!-- frame_id settings -->
<arg name="base_frame_id" default="BODY" />
<arg name="odom_frame_id" default="odom_init" />
<arg name="map_frame_id" default="map" />
<arg name="publish_tf" default="true" />

<!-- image topic settings -->
<arg name="left_image" default="/multisense_local/left/image_rect"/>
<arg name="right_image" default="/multisense_local/right/image_rect"/>
<arg name="left_camera_info" default="/multisense_local/left/camera_info"/>
<arg name="right_camera_info" default="/multisense_local/right/camera_info"/>

<!-- <param name="use_sim_time" type="bool" value="True"/> -->

<!-- Just to uncompress images for stereo_image_rect -->
<!-- <node name="republish_left" type="republish" pkg="image_transport" -->
<!-- args="compressed in:=/stereo_camera/left/image_raw_throttle raw out:=/stereo_camera/left/image_raw_throttle_relay" /> -->
<!-- <node name="republish_right" type="republish" pkg="image_transport" -->
<!-- args="compressed in:=/stereo_camera/right/image_raw_throttle raw out:=/stereo_camera/right/image_raw_throttle_relay" /> -->

<!-- Run the ROS package stereo_image_proc for image rectification -->
<!-- <group ns="/stereo_camera" > -->
<!-- <node pkg="nodelet" type="nodelet" name="stereo_nodelet" args="manager"/> -->
<!-- <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc"> -->
<!-- <remap from="left/image_raw" to="left/image_raw_throttle_relay"/> -->
<!-- <remap from="left/camera_info" to="left/camera_info_throttle"/> -->
<!-- <remap from="right/image_raw" to="right/image_raw_throttle_relay"/> -->
<!-- <remap from="right/camera_info" to="right/camera_info_throttle"/> -->
<!-- <param name="disparity_range" value="128"/> -->
<!-- </node> -->
<!-- </group> -->

<group ns="rtabmap">
<!-- Stereo Odometry -->
<node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry"
output="screen" if="$(arg use_stereo_odometry)">
<remap from="left/image_rect" to="$(arg left_image)"/>
<remap from="right/image_rect" to="$(arg right_image)"/>
<remap from="left/camera_info" to="$(arg left_camera_info)"/>
<remap from="right/camera_info" to="$(arg right_camera_info)"/>
<remap from="odom" to="stereo_odometry"/>

<param name="frame_id" type="string" value="$(arg base_frame_id)"/>
<param name="odom_frame_id" type="string" value="$(arg odom_frame_id)"/> <!-- broadcasted by /footcoords -->
<param name="publish_tf" type="bool" value="$(arg publish_tf)"/>
<!-- <param name="initial_pose" type="string" value="x y z roll pitch yaw"/> -->
<!-- <param name="queue_size" type="int" value="10"/> -->

<param name="Odom/Strategy" type="string" value="0"/> <!-- 0=Frame-to-Map, 1=Frame=to=Frame -->
<param name="Vis/EstimationType" type="string" value="0"/> <!-- 0=3D->3D 1=3D->2D (PnP) -->
<param name="Vis/MaxDepth" type="string" value="10"/>
<param name="Vis/MinInliers" type="string" value="10"/>
<param name="Odom/FillInfoData" type="string" value="false"/>
<param name="GFTT/MinDistance" type="string" value="10"/>
<param name="GFTT/QualityLevel" type="string" value="0.00001"/>
</node>

<!-- Visual SLAM: args: "delete_db_on_start" and "udebug" -->
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen"
args="--delete_db_on_start" if="$(arg use_rtabmap)" respawn="true">
<param name="frame_id" type="string" value="$(arg base_frame_id)"/>
<param name="map_frame_id" type="string" value="$(arg map_frame_id)"/>
<param name="odom_frame_id" type="string" value="$(arg odom_frame_id)"/>
<param name="publish_tf" type="bool" value="$(arg publish_tf)"/>
<param name="subscribe_stereo" type="bool" value="true"/>
<param name="subscribe_depth" type="bool" value="false"/>

<remap from="left/image_rect" to="$(arg left_image)"/>
<remap from="right/image_rect" to="$(arg right_image)"/>
<remap from="left/camera_info" to="$(arg left_camera_info)"/>
<remap from="right/camera_info" to="$(arg right_camera_info)"/>

<remap from="odom" to="stereo_odometry" if="$(arg use_stereo_odometry)"/>
<remap from="odom" to="$(arg odom_topic)" unless="$(arg use_stereo_odometry)"/>
<remap from="proj_map" to="/map"/>

<param name="queue_size" type="int" value="30"/>
<!-- <param name="grid_cell_size" value="0.025"/> -->
<!-- <param name="scan_voxel_size" value="0.025"/> -->
<!-- <param name="cloud_voxel_size" value="0.025"/> -->

<!-- RTAB-Map's parameters -->
<param name="Rtabmap/TimeThr" type="string" value="700"/>
<param name="Kp/MaxFeatures" type="string" value="200"/>
<param name="Kp/MaxDepth" type="string" value="10"/>
<param name="Kp/DetectorStrategy" type="string" value="0"/> <!-- use SURF -->
<param name="SURF/HessianThreshold" type="string" value="1000"/>
<param name="Vis/EstimationType" type="string" value="0"/> <!-- 0=3D->3D, 1=3D->2D (PnP) -->
<param name="RGBD/LoopClosureReextractFeatures" type="string" value="true"/>
<param name="Vis/MaxDepth" type="string" value="10"/>
</node>
</group>

<!-- Visualisation RVIZ -->
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find rtabmap_ros)/launch/config/demo_stereo_outdoor.rviz"
if="$(arg use_rviz)" />

</launch>