|
20 | 20 | from launch import LaunchDescription |
21 | 21 | from chonkur_deploy.launch_helpers import include_launch_file |
22 | 22 | from launch_ros.actions import Node |
| 23 | +from launch.substitutions import ( |
| 24 | + Command, |
| 25 | + FindExecutable, |
| 26 | + PathJoinSubstitution, |
| 27 | +) |
| 28 | +from launch_ros.substitutions import ( |
| 29 | + FindPackageShare, |
| 30 | +) |
23 | 31 |
|
24 | 32 |
|
25 | 33 | def generate_launch_description(): |
26 | 34 |
|
27 | 35 | declared_arguments = [] |
28 | 36 |
|
29 | | - Node( |
| 37 | + clr_mujoco_package_name = "clr_mujoco_config" |
| 38 | + clr_mujoco_description_file = "clr_xacro.urdf" |
| 39 | + |
| 40 | + mjcf_robot_description_content = Command( |
| 41 | + [ |
| 42 | + PathJoinSubstitution([FindExecutable(name="xacro")]), |
| 43 | + " ", |
| 44 | + PathJoinSubstitution([FindPackageShare(clr_mujoco_package_name), "urdf", clr_mujoco_description_file]), |
| 45 | + # Grasp frames should not be converted to MJCF objects |
| 46 | + " add_grasp_push_frames:=false", |
| 47 | + " model_env:=true", |
| 48 | + ] |
| 49 | + ) |
| 50 | + |
| 51 | + generate_mjcf = Node( |
30 | 52 | package="mujoco_ros2_control", |
31 | 53 | executable="robot_description_to_mjcf.sh", |
32 | 54 | output="both", |
33 | 55 | emulate_tty=True, |
34 | | - arguments=["--publish_topic", "/mujoco_robot_description"], |
| 56 | + arguments=[ |
| 57 | + "--publish_topic", |
| 58 | + "/mujoco_robot_description", |
| 59 | + "--robot_description", |
| 60 | + mjcf_robot_description_content, |
| 61 | + "--convert_stl_to_obj", |
| 62 | + "--asset_dir", |
| 63 | + # PathJoinSubstitution([FindPackageShare(clr_mujoco_package_name), "description", "assets"]), |
| 64 | + "/home/er4-user/ws/src/mjcf_data/assets", |
| 65 | + ], |
35 | 66 | ) |
36 | 67 |
|
37 | 68 | clr_launch = include_launch_file( |
@@ -63,4 +94,4 @@ def generate_launch_description(): |
63 | 94 | ], |
64 | 95 | ) |
65 | 96 |
|
66 | | - return LaunchDescription(declared_arguments + [clr_launch, point_cloud_proc]) |
| 97 | + return LaunchDescription(declared_arguments + [generate_mjcf, clr_launch, point_cloud_proc]) |
0 commit comments