Skip to content

Commit

Permalink
Perception: Adjusting to the changes made that were meant to address m…
Browse files Browse the repository at this point in the history
  • Loading branch information
130s committed Jun 22, 2023
1 parent 22ce5ba commit bb901d8
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
<include file="$(find-pkg-share moveit2_tutorials)/launch/obstacle_avoidance_demo.launch.xml" />

<!-- Run the detection and adding cylinder node -->
<node pkg="moveit2_tutorials" exec="cylinder_segment" name="point_cloud_preprocessor" />
<node pkg="moveit2_tutorials" exec="detect_and_add_cylinder_collision_object_demo" name="point_cloud_preprocessor" />

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,24 @@
<arg name="bagfile" default="$(find-pkg-share moveit2_tutorials)/bags/perception_tutorial.bag" />
<arg name="launchfile_panda"
default="$(find-pkg-share moveit_resources_panda_moveit_config)/launch/demo.launch.py" />

<!--
In this tutorial we wait much longer for the robot transforms than we usually would,
because the user's machine might be quite slow.
Arg name is shortened although the final lengthy Param name is: 'robot_description_planning/shape_transform_cache_lookup_wait_tim'
-->
<param name="robot_description_planning/shape_transform_cache_lookup_wait_time" value="0.5" />
<arg name="shape_transform_cache_lookup_wait_time"
default="0.5" />

<!-- Play the rosbag that contains the pointcloud data -->
<executable cmd="ros2 bag play -l $(var bagfile)" output="screen" />

<include file="$(var launchfile_panda)" />
<include file="$(var launchfile_panda)">
<arg name="shape_transform_cache_lookup_wait_time"
value="$(var shape_transform_cache_lookup_wait_time)" />
</include>

<!-- If needed, broadcast static tf for robot root -->
<node pkg="tf2_ros" exec="static_transform_publisher" name="to_panda" args="0 0 0 0 0 0 world panda_link0" />
<node pkg="tf2_ros" type="static_transform_publisher" name="to_camera" args="0.00 -.40 0.60 0.19 0.07 -1.91 world camera_rgb_optical_frame" />
<node pkg="tf2_ros" exec="static_transform_publisher" name="to_camera" args="0.00 -.40 0.60 0.19 0.07 -1.91 world camera_rgb_optical_frame" />

</launch>

0 comments on commit bb901d8

Please sign in to comment.