wip: updated sim launchfile
This commit is contained in:
@@ -46,10 +46,27 @@ def generate_launch_description():
|
|||||||
}]
|
}]
|
||||||
)
|
)
|
||||||
|
|
||||||
joint_pub = Node(
|
# Load controller manager
|
||||||
package='joint_state_publisher',
|
#control_manager = Node(
|
||||||
executable='joint_state_publisher',
|
# package='controller_manager',
|
||||||
name='joint_state_publisher',
|
# executable='ros2_control_node',
|
||||||
|
# parameters=[{'use_sim_time': True}, {'robot_description': '/robot_description'}],
|
||||||
|
# output='screen'
|
||||||
|
#)
|
||||||
|
|
||||||
|
# Spawner for the mecanum controller
|
||||||
|
controller = Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='spawner',
|
||||||
|
arguments=['mecanum_controller'],
|
||||||
|
output='screen'
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_broadcaster = Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='spawner',
|
||||||
|
arguments=['joint_state_broadcaster', '--controller-manager', '/controller_manager'],
|
||||||
|
parameters=[{'use_sim_time': True}],
|
||||||
output='screen'
|
output='screen'
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -60,8 +77,8 @@ def generate_launch_description():
|
|||||||
arguments=[
|
arguments=[
|
||||||
'0', '0', '0',
|
'0', '0', '0',
|
||||||
'0', '0', '0',
|
'0', '0', '0',
|
||||||
'lidar_link',
|
'velodyne',
|
||||||
'camera_init',
|
'base_link',
|
||||||
]
|
]
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -76,17 +93,13 @@ def generate_launch_description():
|
|||||||
)
|
)
|
||||||
|
|
||||||
gz_bridge = Node(
|
gz_bridge = Node(
|
||||||
package='ros_gz_bridge',
|
package="ros_gz_bridge",
|
||||||
executable='parameter_bridge',
|
executable="parameter_bridge",
|
||||||
arguments=[
|
arguments=[
|
||||||
'/velodyne_points/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked',
|
"--ros-args",
|
||||||
'/model/sherpa/joint_states@gz.msgs.Model_JointState@ros2/sensor_msgs/msg/JointState',
|
"-p",
|
||||||
],
|
f"config_file:={os.path.join(get_package_share_directory('sherpa'), 'config', 'gz_bridge.yaml')}",
|
||||||
remappings=[
|
]
|
||||||
('/velodyne_points/points', '/velodyne_points'),
|
|
||||||
('/model/sherpa/joint_states', '/joint_states'),
|
|
||||||
],
|
|
||||||
output='screen'
|
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
@@ -99,10 +112,12 @@ def generate_launch_description():
|
|||||||
ld.add_action(gz_env)
|
ld.add_action(gz_env)
|
||||||
ld.add_action(gz)
|
ld.add_action(gz)
|
||||||
ld.add_action(state_publisher)
|
ld.add_action(state_publisher)
|
||||||
ld.add_action(joint_pub)
|
|
||||||
ld.add_action(static_tf)
|
ld.add_action(static_tf)
|
||||||
ld.add_action(robot)
|
ld.add_action(robot)
|
||||||
ld.add_action(gz_bridge)
|
ld.add_action(gz_bridge)
|
||||||
|
ld.add_action(joint_state_broadcaster)
|
||||||
|
ld.add_action(controller)
|
||||||
|
#ld.add_action(control_manager)
|
||||||
ld.add_action(rviz2)
|
ld.add_action(rviz2)
|
||||||
|
|
||||||
return ld
|
return ld
|
||||||
|
|||||||
Reference in New Issue
Block a user