From 5badec1c5cafe3b6725bea959babba7d73f9609e Mon Sep 17 00:00:00 2001 From: "Isaac I.Y. Saito" <130s@2000.jukuin.keio.ac.jp> Date: Fri, 9 Jun 2023 14:36:18 -0400 Subject: [PATCH] Improve: panda_moveit: Add parameters for perception tutorial --- panda_moveit_config/launch/demo.launch.py | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/panda_moveit_config/launch/demo.launch.py b/panda_moveit_config/launch/demo.launch.py index 12e74017..6c491825 100644 --- a/panda_moveit_config/launch/demo.launch.py +++ b/panda_moveit_config/launch/demo.launch.py @@ -9,6 +9,22 @@ from moveit_configs_utils import MoveItConfigsBuilder +def _octomap_launch_params(): + _path_panda_sensor_conf = PathJoinSubstitution( + [ + FindPackageShare("panda_moveit_config"), + "config", + "sensors_kinect_pointcloud.yaml" + ]) + _params = [ + launch_ros.parameter_descriptions.ParameterFile( + param_file=_path_panda_sensor_conf, + allow_substs=True), + {"octomap_frame": "odom_combined"}, + {"octomap_resolution": "0.05"}, + {"max_range": "5.0"}] + return _params + def generate_launch_description(): # Command-line arguments @@ -49,7 +65,7 @@ def generate_launch_description(): package="moveit_ros_move_group", executable="move_group", output="screen", - parameters=[moveit_config.to_dict()], + parameters=[moveit_config.to_dict(), _octomap_launch_params()], arguments=["--ros-args", "--log-level", "info"], )