-
Notifications
You must be signed in to change notification settings - Fork 98
/
racecar_control.launch
28 lines (21 loc) · 1.36 KB
/
racecar_control.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
<?xml version='1.0'?>
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find racecar_control)/config/racecar_control.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_manager" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/racecar" args="left_rear_wheel_velocity_controller right_rear_wheel_velocity_controller
left_front_wheel_velocity_controller right_front_wheel_velocity_controller
left_steering_hinge_position_controller right_steering_hinge_position_controller
joint_state_controller"/>
<!-- convert joint states to TF transforms for rviz, etc -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen">
<remap from="/joint_states" to="/racecar/joint_states" />
</node>
<!-- servo node -->
<node pkg="racecar_control" type="servo_commands.py" name="servo_commands" output="screen">
<remap from="/racecar/ackermann_cmd_mux/output" to="/vesc/low_level/ackermann_cmd_mux/output"/>
</node>
<!-- Allow for Gazebo to broadcast odom -->
<node pkg="racecar_gazebo" name="gazebo_odometry_node" type="gazebo_odometry.py"/>
</launch>