|
1 | 1 | import os |
2 | 2 | from launch import LaunchDescription |
3 | 3 | from launch.actions import DeclareLaunchArgument |
4 | | -from launch.substitutions import LaunchConfiguration |
| 4 | +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution |
5 | 5 | from launch.conditions import IfCondition, UnlessCondition |
| 6 | +import launch_ros |
6 | 7 | from launch_ros.actions import Node |
7 | 8 | from launch.actions import ExecuteProcess |
8 | 9 | from ament_index_python.packages import get_package_share_directory |
9 | 10 | from moveit_configs_utils import MoveItConfigsBuilder |
10 | 11 |
|
11 | 12 |
|
| 13 | +def _octomap_launch_params(): |
| 14 | + _path_panda_sensor_conf = PathJoinSubstitution( |
| 15 | + [ |
| 16 | + launch_ros.substitutions.FindPackageShare("panda_moveit_config"), |
| 17 | + "config", |
| 18 | + "sensors_kinect_pointcloud.yaml" |
| 19 | + ]) |
| 20 | + _params = [ |
| 21 | + launch_ros.parameter_descriptions.ParameterFile( |
| 22 | + param_file=_path_panda_sensor_conf, |
| 23 | + allow_substs=True), |
| 24 | + {"octomap_frame": "odom_combined"}, |
| 25 | + {"octomap_resolution": "0.05"}, |
| 26 | + {"max_range": "5.0"}] |
| 27 | + return _params |
| 28 | + |
12 | 29 | def generate_launch_description(): |
13 | 30 |
|
14 | 31 | # Command-line arguments |
@@ -49,7 +66,7 @@ def generate_launch_description(): |
49 | 66 | package="moveit_ros_move_group", |
50 | 67 | executable="move_group", |
51 | 68 | output="screen", |
52 | | - parameters=[moveit_config.to_dict()], |
| 69 | + parameters=[moveit_config.to_dict()] + _octomap_launch_params(), |
53 | 70 | arguments=["--ros-args", "--log-level", "info"], |
54 | 71 | ) |
55 | 72 |
|
|
0 commit comments