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

[Tempolary] Added jaxon_multisense_rtabmap.launch. #194

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
83 changes: 83 additions & 0 deletions hrpsys_choreonoid_tutorials/launch/jaxon_multisense_rtabmap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
<launch>

<!-- Choose visualization -->
<!-- <arg name="rviz" default="true" /> -->

<!-- <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">
<remap from="left/image_rect" to="/multisense_local/left/image_rect"/>
<remap from="right/image_rect" to="/multisense_local/right/image_rect"/>
<remap from="left/camera_info" to="/multisense_local/left/camera_info"/>
<remap from="right/camera_info" to="/multisense_local/right/camera_info"/>
<remap from="odom" to="/stereo_odometry"/>

<param name="frame_id" type="string" value="BODY"/>
<param name="odom_frame_id" type="string" value="odom_init"/> <!-- broadcasted by /footcoords -->
<param name="publish_tf" type="bool" value="true"/>
<!-- <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">
<param name="frame_id" type="string" value="BODY"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="odom_frame_id" type="string" value="odom_init"/>
<param name="publish_tf" type="bool" value="true"/>
<param name="subscribe_stereo" type="bool" value="true"/>
<param name="subscribe_depth" type="bool" value="false"/>

<remap from="left/image_rect" to="/multisense_local/left/image_rect"/>
<remap from="right/image_rect" to="/multisense_local/right/image_rect"/>
<remap from="left/camera_info" to="/multisense_local/left/camera_info"/>
<remap from="right/camera_info" to="/multisense_local/right/camera_info"/>

<remap from="odom" to="/stereo_odometry"/>
<param name="queue_size" type="int" value="30"/>

<!-- 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"/>

</launch>