-
Notifications
You must be signed in to change notification settings - Fork 229
Controlling the AutoRally Platform
This tutorial describes how to control a physical or simulated AutoRally platform with your own controller.
The AutoRally platform has 3 actuators, all controlled by the same message:
- steering
- throttle/rear brake
- front brake
The autorally_chassis
nodelet allows any program to control any actuator by following the steps described below. At any one time, there can be many nodes publishing autorally_msgs/chassisCommand
messages to their own chassisCommand
topics. The autorally_chassis
receives all of these messages and selects the highest priority valid command for each actuator. This design allows different programs to control different actuators at the same time such as independent steering and throttle controllers. This structure supports seamless, automatic switching between controllers according to their priorities by having high priority controllers cede control to lower priority controllers as desired. The autorally_chassis
translates each actuator command to a PWM signal taking into consideration the arChassisConfig chassis calibration .yaml file and sends them to the actuators.
You must choose a string name to refer to your controller. The easiest choice is the node name, but it really doesn't matter as long as it is unique. This string will be referred to as
YOUR_SERVO_COMMANDER
for the rest of the tutorial.
The maximum meaningful control rate for all of the actuators is 50 hz, limited by the PWM period that the actuators accept. There is no torque or position control available through the
autorally_chassis
for the same reason. If you send control commands faster than the maximum control rate, the most recent message received during the previous time window will be used, and all others will be ignored.
The autorally_chassis will only accept the autorally_msgs/chassisCommand
message that satisfies the following format:
- Header
stamp
contains current timestamp (msg->header.stamp = ros::Time::now()
) -
sender
isYOUR_SERVO_COMMANDER
- Valid actuator values are [-1, 1], anything out of this range signals to the
autorally_chassis
you do not want to control the actuator -
steering
- -1 is full left
- 0 is straight
- 1 is full right
-
throttle
- -1 is full electronic brake
- 0 is no throttle (coast)
- 1 is full throttle
Throttle and rear brake are part of the same signal and therefore cannot be controlled independently.
-
frontBrake
- less than 0 is ignored
- 0 is no brake
- 1 is full front brake
- Add
YOUR_SERVO_COMMANDER
with a unique priority number to your copy ofautorally/autorally_util/config/servoCommandPrioritites.yaml
. Valid priority values are unique, positive integers. Lower values have higher priority and 0 has the highest priority. Priority values do not have to be sequential. - Configure your controller to publish an
autorally_msgs/chassisCommand
message to the topic/YOUR_SERVO_COMMANDER/chassisCommand
at a rate between 10Hz-50Hz with your desired actuator values and configured header - If you do not want to control an actuator, set it's respective command value in the chassisCommand message to something outside the valid range (-5 is a good choice)
- With the
autorally_chassis
(started as part of autorally.launch) orautorally_controller
(started as part of the simulation) and your controller running, verify the chassis interface is subscribed to your chassisCommand topic usingrqt_graph
. - runstopMotionEnabled in the
/chassisState
topic by autorally_chassis and displayed in the OCS must be 1 to enable autonomous throttle control. The runstopMotionEnabled in/chassisState
is an or of all valid runstop messages received. The OCS and joystick nodes both publish runstop messages.
- A simple example node that publishes a chassisCommand message is the autorally_control joystick node.
- The physical and simulation platform are controlled by the same message.
- For the lowest latency control, design your controller as a nodelet and load it into
autorally_core_manager
nodelet manager, which is the same nodelet manager theautorally_chassis
nodelet loads into. Make sure to follow the ROS Intraprocess Publishing instructions instructions for publishing chassisCommand.
If your control nodelet loaded into the
autorally_core_manager
nodelet manager crashes, it will take down the autorally_chassis
with it.
- Refer to the Operating Procedures if you have questions about running core AutoRally software.