quadruped_ros2_control/libraries/gz_quadruped_playground/launch/ocs2.launch.py

94 lines
2.9 KiB
Python
Raw Normal View History

2025-02-23 22:07:46 +08:00
import xacro
from launch import LaunchDescription
2025-03-22 00:15:54 +08:00
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
2025-02-23 22:07:46 +08:00
from launch.event_handlers import OnProcessExit
from launch_ros.actions import Node
2025-03-22 00:15:54 +08:00
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
2025-02-23 22:07:46 +08:00
def generate_launch_description():
joint_state_publisher = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster",
"--controller-manager", "/controller_manager"]
)
imu_sensor_broadcaster = Node(
package="controller_manager",
executable="spawner",
arguments=["imu_sensor_broadcaster",
"--controller-manager", "/controller_manager"]
)
ocs2_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
)
2025-03-22 00:15:54 +08:00
elevation_mapping = Node (
package="elevation_mapping",
executable="elevation_mapping",
parameters=[
PathJoinSubstitution(
[
FindPackageShare("ocs2_quadruped_controller"),
"config",
"elevation_mapping.yaml",
]
)
],
)
elevation_mapping = Node (
package="elevation_mapping",
executable="elevation_mapping",
parameters=[
PathJoinSubstitution(
[
FindPackageShare("ocs2_quadruped_controller"),
"config",
"elevation_mapping.yaml",
]
)
],
)
convex_plane_decomposition = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare("convex_plane_decomposition_ros"),
"launch",
"convex_plane_decomposition.launch.py"
])
]),
launch_arguments={
"parameter_file": PathJoinSubstitution([
FindPackageShare("legged_perceptive_controllers"),
"config",
"convex_plane_decomposition.yaml"
])
}.items()
)
2025-02-23 22:07:46 +08:00
return LaunchDescription([
2025-02-25 22:18:55 +08:00
joint_state_publisher,
2025-03-22 00:15:54 +08:00
# elevation_mapping,
# convex_plane_decomposition,
2025-02-25 22:18:55 +08:00
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_publisher,
on_exit=[imu_sensor_broadcaster],
)
),
2025-02-23 22:07:46 +08:00
RegisterEventHandler(
event_handler=OnProcessExit(
2025-02-25 22:18:55 +08:00
target_action=imu_sensor_broadcaster,
on_exit=[ocs2_controller],
2025-02-23 22:07:46 +08:00
)
),
])