Files
ros2_roboclaw_driver/config/motor_driver.yaml
Michael Wimble 140da45bcb Ready for merge.
2025-03-31 11:18:18 -07:00

75 lines
2.8 KiB
YAML
Executable File

# The configuration file provides values for the two, differential
# drive motors, 'm1' and 'm2'. See the article:
# https://resources.basicmicro.com/auto-tuning-with-motion-studio/
# for a description of how to derive the p, i, d and qpps values.
#
# This configuration file is set up and an example for use with
# A Raspberry PI 5 using a UART to connect to a RoboClaw motor driver.
# See the README.md file for more information on how to set up
# the RoboClaw and the Raspberry PI and how to set values in this file.
motor_driver_node:
ros__parameters:
# Incremental acceleration to use in quadrature pulses per second.
accel_quad_pulses_per_second: 1000
# The device name to be opened. Change this to your actual device you are using.
# Both USB and UART devices are supported. The device name is the
# name of the device as it appears in the /dev directory.
device_name: "/dev/ttyAMA0"
baud_rate: 38400 # This does not apply when using USB.
# The assigned port for the device (as configured on the RoboClaw).
device_port: 128
# The P, I, D and maximum quadrature pulses per second for both motors.
# These values are for my robot. Replace them with your own values.
# Use can use Basic Micro's Motion Studio to determine the values.
m1_p: 7.26239
m1_i: 1.36838
m1_d: 0.0
m1_qpps: 2437
m2_p: 7.26239
m2_i: 1.28767
m2_d: 0.0
m2_qpps: 2437
# The maximum expected current (in amps) for both motors.
# Used just to signal warnings.
m1_max_current: 6.0
m2_max_current: 6.0
# Rate limiting commands. The driver will clip any value
# exceeding these limits.
max_angular_velocity: 0.07
max_linear_velocity: 0.3
# If no new motor commands is received since the last motor
# command in this number of seconds, stop the motors.
max_seconds_uncommanded_travel: 0.25
publish_joint_states: false
publish_odom: true
# Based upon your particular motor gearing and encoders.
# These values are used to scale cmd_vel commands
# and encoder values to motor commands and odometry, respectfully.
quad_pulses_per_meter: 1566
quad_pulses_per_revolution: 979.62
# Based upon y our particular robot model.
# The wheel separation and radius, in meters.
wheel_radius: 0.10169
wheel_separation: 0.345
# Topic name to be used to publish the RoboClaw status messages.
roboclaw_status_topic: "roboclaw_status"
# How often, in Hz, to sense the various RoboClaw internal values.
# This is the rate that Joint State, Odomentry and
# RoboClaw status messages are published.
sensor_rate_hz: 20.0
# Debugging control.
do_debug: false # True => Log RoboClaw commands and responses.
do_low_level_debug: false # True => Log low-level serial and RoboClaw data.