Permalink
Switch branches/tags
Nothing to show
Find file Copy path
Fetching contributors…
Cannot retrieve contributors at this time
51 lines (47 sloc) 1.35 KB
joy_node:
deadzone: 0.01
autorepeat_rate: 20
coalesce_interval: 0.01
teleop:
# Default mode - Stop for safety
default:
type: topic
is_default: true
message_type: ackermann_msgs/AckermannDriveStamped
topic_name: low_level/ackermann_cmd_mux/input/teleop
message_value:
-
target: drive.speed
value: 0.0
-
target: drive.steering_angle
value: 0.0
# Enable Human control by holding Left Bumper
human_control:
type: topic
message_type: ackermann_msgs/AckermannDriveStamped
topic_name: low_level/ackermann_cmd_mux/input/teleop
deadman_buttons: [4]
axis_mappings:
-
axis: 1
target: drive.speed
scale: 2.0 # joystick will command plus or minus 2 meters / second
offset: 0.0
-
axis: 3
target: drive.steering_angle
scale: 0.34 # joystick will command plus or minus ~20 degrees steering angle
offset: 0.0
# Enable autonomous control by pressing right bumper
# This switch causes the joy_teleop to stop sending messages to input/teleop
# And send messages to /dev/null (an unused ROS topic)
autonomous_control:
type: topic
message_type: std_msgs/Int8
topic_name: /dev/null
deadman_buttons: [5]
message_value:
-
target: data
value: 0