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

updates sample launch file #28

Merged
merged 1 commit into from
Feb 8, 2017
Merged
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
16 changes: 13 additions & 3 deletions launch/test.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
<launch>
<arg name="map_objs" />
<arg name="use_pointcloud_map" default="false" />
<arg name="map_objs" unless="$(arg use_pointcloud_map)" />
<arg name="map_pcd" if="$(arg use_pointcloud_map)" />
<arg name="map_scale" default="1.0" />
<arg name="map_offset_x" default="0.0" />
<arg name="map_offset_y" default="0.0" />
Expand All @@ -14,8 +16,9 @@
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find mcl_3dl)/launch/mcl_3dl.rviz" />
<node pkg="mcl_3dl" type="mcl_3dl" name="mcl_3dl" output="screen">
<remap from="~/cloud" to="/cloud" />
<remap from="~/mapcloud" to="/obj_to_pointcloud/cloud" />
<remap from="~/mapcloud" to="/mapcloud" />
<remap from="~/odom" to="/odom" />
<remap from="~/imu" to="/imu/data" />
<remap from="~/initialpose" to="/initialpose" />
<param name="num_particles" value="64" />
<param name="num_points" value="96" />
Expand All @@ -26,13 +29,20 @@
<param name="jump_dist" value="1.0" />
<param name="jump_ang" value="1.57" />
</node>
<node pkg="obj_to_pointcloud" type="obj_to_pointcloud" name="obj_to_pointcloud">
<node pkg="obj_to_pointcloud" type="obj_to_pointcloud" name="obj_to_pointcloud"
unless="$(arg use_pointcloud_map)">
<param name="objs" value="$(arg map_objs)" />
<param name="points_per_meter_sq" value="1200.0" />
<param name="offset_x" value="$(arg map_offset_x)" />
<param name="offset_y" value="$(arg map_offset_y)" />
<param name="downsample_grid" value="0.1" />
<param name="scale" value="$(arg map_scale)" />
<remap from="~/cloud" to="/mapcloud" />
</node>
<node pkg="pcl_ros" type="pcd_to_pointcloud" name="pcd_to_pointcloud"
args="$(arg map_pcd)" if="$(arg use_pointcloud_map)">
<param name="frame_id" value="map" />
<remap from="/cloud_pcd" to="/mapcloud" />
</node>
<node pkg="track_odometry" type="track_odometry" name="track_odometry">
<remap from="/imu" to="/imu/data" />
Expand Down