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_tilt_laser] Add Multisense local option #857

Merged
merged 3 commits into from
Apr 12, 2015
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
31 changes: 22 additions & 9 deletions jsk_tilt_laser/launch/multisense.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,27 @@
<arg name="not_use_sensor_tf_prefix" default="false" />
<arg name="run_driver" default="true" />
<arg name="fixed_frame_id" default="head_root" />

<include file="$(find multisense_bringup)/multisense.launch" if="$(arg run_driver)">
<arg name="ip_address" value="$(arg ip_address)" />
<arg name="namespace" value="$(arg namespace)" />
<arg name="mtu" value="$(arg mtu)" />
<arg name="launch_robot_state_publisher" value="$(arg use_robot_description)" />
</include>

<!-- if 'use_resize' is true, run nodelets to publish resized stereo pointcloud-->
<arg name="use_resize" default="true" />
<!--
If 'local' argument is true, remapping stereo pointcloud
from multisense/foo to multisense_local/foo.
If you use with local true, we recommend to set use_resize false.
-->
<arg name="local" default="false" />
<group>
<!-- Remapping for 'local:=true' -->
<remap from="/multisense/left/image_rect_color" to="/multisense_local/left/image_rect_color" if="$(arg local)"/>
<remap from="/multisense/image_points2_color" to="/multisense_local/image_points2_color" if="$(arg local)"/>
<remap from="/multisense/organized_image_points2" to="/multisense_local/organized_image_points2" if="$(arg local)"/>
<remap from="/multisense/organized_image_points2_color" to="/multisense_local/organized_image_points2_color" if="$(arg local)"/>
<include file="$(find multisense_bringup)/multisense.launch" if="$(arg run_driver)">
<arg name="ip_address" value="$(arg ip_address)" />
<arg name="namespace" value="$(arg namespace)" />
<arg name="mtu" value="$(arg mtu)" />
<arg name="launch_robot_state_publisher" value="$(arg use_robot_description)" />
</include>
</group>
<!--
Overwrite multisense/multisense_driver/tf_prefix parameter.
Because this parameter affects frame_id of images, lasers.
Expand Down Expand Up @@ -120,7 +133,7 @@
<node pkg="dynamic_reconfigure" type="dynparam" args="set /multisense motor_speed 0.5" name="set_multisense_spindle_speed" />
<node pkg="dynamic_reconfigure" type="dynparam" args="set /multisense fps 30.0" name="set_multisense_fps" />

<include file="$(find jsk_pcl_ros)/launch/multi_resolution_organized_pointcloud.launch">
<include file="$(find jsk_pcl_ros)/launch/multi_resolution_organized_pointcloud.launch" if="$(arg use_resize)">
<arg name="NAMESPACE" value="multisense" />
<arg name="INPUT" value="/multisense/organized_image_points2_color" />
</include>
Expand Down
35 changes: 35 additions & 0 deletions jsk_tilt_laser/launch/multisense_remote.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<launch>
<arg name="namespace" default="multisense" />
<arg name="use_resize" default="true" />
<!-- Run stereo_image_proc -->

<group ns="$(arg namespace)">
<node pkg="nodelet" type="nodelet" name="stereo_manager"
args="manager" />
<node pkg="nodelet" type="nodelet" name="left_image_rect_color_relay"
args="load jsk_topic_tools/Relay stereo_manager">
<remap from="~input" to="/$(arg namespace)_local/left/image_rect_color" />
<remap from="~output" to="/$(arg namespace)/left/image_rect_color" />
</node>
<node pkg="nodelet" type="nodelet" name="point_cloud_xyz"
args="load depth_image_proc/point_cloud_xyz stereo_manager">
<remap from="camera_info" to="depth/camera_info" />
<remap from="image_rect" to="depth" />
<remap from="points" to="organized_image_points2" />
</node>
<node pkg="nodelet" type="nodelet" name="point_cloud_xyzrgb"
args="load depth_image_proc/point_cloud_xyzrgb stereo_manager">
<remap from="rgb/camera_info" to="/$(arg namespace)_local/left/camera_info" />
<remap from="rgb/image_rect_color" to="left/image_rect_color" />
<remap from="depth_registered/image_rect" to="depth" />
<remap from="depth_registered/points" to="organized_image_points2_color" />
</node>
</group>
<include file="$(find jsk_pcl_ros)/launch/multi_resolution_organized_pointcloud.launch" if="$(arg use_resize)">
<arg name="NAMESPACE" value="multisense" />
<arg name="INPUT" value="/multisense/organized_image_points2_color" />
<arg name="RUN_MANAGER" value="false" />
<arg name="MANAGER" value="/$(arg namespace)/stereo_manager" />
</include>

</launch>