Driver Interface discussion
Present at discussion:
- Piyush Khandelwal
- Jack O'Quin
- Cedric Pradalier
- Chien-Liang Fok
- Austin Hendrix
- Ken Conley
Contents
Meeting agenda
Discuss a common driver interface for Ackermann steering based robots. Develop a generic controller similar to teleop_twist_keyboard for Ackermann robots.
Question / concerns / comments
Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.
(Piyush) What are the needs that different groups have beyond velocity and steering angle.
(Cedric) Some comments for completeness: for some systems, a torque (in N.m) or a throttle value (in %) might be more relevant, even if there could well be a low-level controller taking care of reaching the velocity set-point. Real cars or some industrial platforms also have a brake (which you sometimes activate at the same times as the throttle). Similarly, some control laws assume that the system is commanded in steering velocity. Steering torque might even be useful for an autonomous bike.
(Liang) How about let's include acceleration parameters for both velocity (in m/s2 ) and steering angle (deg/s2)? This may reduce the number of times speed updates need to be sent, but will require the low-level micro-controller within the mobility chassis to be more complex. If acceleration is infrequently changed, we can have two separate messages: one to set the velocity/rotation values, and another to set the acceleration parameters.
(Jack) This could be handled in a device-dependent ROS node, not necessarily a micro-controller. The goal is to define a generic interface for navigating car-like vehicles.
(Liang) I'm having second thoughts about the acceleration parameter. My assumption was that a vehicle could maintain a linear acceleration as it changed from its current velocity to the new target velocity. This is not true, for example, if a PID controller is used. The question then becomes should we reveal the actual acceleration behavior through the API, and if so, to what degree of accuracy? Perhaps we can provide an API for the setpoint scheduling technique described in T.-C. Au, M. Quinlan, and P. Stone, "Setpoint Scheduling for autonomous Vehicle Controllers," ICRA 2012.
(Jack) Michael Quinlan and I held a review last year in which we defined the art_msgs/CarDrive message. For our vehicle, a full-size car, we concluded that both acceleration and jerk should be provided (in addition to velocity). It is hard to drive smoothly without limiting the rate of change of acceleration.
(Jack) One can control acceleration by manipulating the throttle or brake using accelerometers for PID feedback. In practice, PID on the speed itself is also necessary for times when no acceleration is needed. The simplest solution is to do speed PID, and incrementally adjust the set point based on the requested jerk and acceleration. Surprisingly, that works quite well.
(Liang) Perhaps instead of an acceleration we could specify a temporal deadline. That is, the vehicle must accelerate (or decelerate) to the new target speed by a certain time, but how it achieves this is up to the vehicle.
(Jack) That seems difficult to me. Acceleration is a relatively direct function of device-dependent brake and throttle settings. Deadlines are much higher-level concepts, probably involving differential equations. EDIT: that was wrong, I was confused by the problem of distance deadlines (like stopping at a desired location), not time deadlines.
(Liang) How accurately do we (the users of our API) expect the robot to follow the acceleration and jerk parameters? Are they just general guidelines? Do we expect the robot to actually accelerate or jerk at the specified values? Since the actual kinetic behavior of the robot is very complex, I was hoping we could abstract it away by simply providing a temporal deadline.
(Jack) We defined acceleration and jerk as desired absolute values for the second and third derivatives, preferably not to be exceeded. The actual controller may ignore them completely or use them for general guidance. Sometimes it will need to use smaller values. When one of them is set to zero, the next lower derivative is permitted to change as quickly as possible. I suspect that for smooth operation most navigation nodes will provide relatively constant values for acceleration and jerk, except when making an emergency stop or other accident-avoidance maneuver.
(Cedric) Do we want to assume from the beginning that we're only discussing systems for which the velocity loop and the steering loop are implemented in the low-level interface? I find it difficult to define a generic interface below the velocity/steering angle interface.
(Liang) Yes. I think velocity and steering angle should be the parameters of the lowest level interface, along with the corresponsing acceleration parameters.
(Piyush) I agree. I believe velocity and steering will be at the lowest levels.
(Jack) +1; plus I think we should include acceleration and jerk, too.
(Cedric) Should we define from the beginning that the velocity is the speed of the center of the rear (e.g. non-steering) axle?
(Liang) I vote yes. Also, instead of velocity, maybe it should be speed (i.e., direction-less). This way it will not depend on the angle of the front wheels.
(Piyush). I am against making velocity direction-less, as it makes it difficult to define going in reverse. I am also not sure I understand your 2nd point.
(Liang). Reverse direction can be specified using a negative speed. My point is a velocity in a plane consists of an x and y component while the rear wheels of a car-like robot can only obey the x component (assuming x is the forward/backward direction). Thus, instead of specifying the steering angle and velocity in a motion command, it may be better to specify the steering angle (of the front wheels) and speed (of the rear wheels).
(Piyush) +1. This is what we do for our autonomous car as well
(Jack) +1; speed (scalar magnitude of the velocity vector) is what we want. There must be some way to distinguish reverse motion, negative speed is one option. We've used that before, and Stage uses that convention with drive-mode car. Alternatively, the gear could be specified, with reverse explicitly mentioned.
(Austin). Rather than using the center of the rear axle, I vote we use the point on the robot tangent to the turning radius to define velocity. For platforms with only front steering, this will be the rear axle. For platforms with dual steering, this will be somewhere near the middle of the robot. This also corresponds to the traditional cmd_vel.linear.x
(Cedric) I personally think we should restrict ourselves to bike-like (car-like) geometry, with a single steerable axle. The point for which the velocity vector is tangent to the turning arc is moving as soon as we have multiple independent steerings (see here), so specifying its velocity might be a challenge in itself. And what about planetary rovers with 6+ steered-wheels?
(Liang) I vote for restricting ourselves to bike/car-like geometry (i.e., with a single steering axle) because it's simpler and more intuitive. We can later provide a more general/complex API that builds our initial one and supports vehicles with many steerable axles. Thus, for our current API, I think we should keep it simple and define speed to be the distance the center of the rear axle moves per unit time.
(Jack) +1; navigation algorithms are highly dependent on the capabilities and limitations of the underlying device. A path planner for an Ackermann drive vehicle differs from one for a holonomic robot, or for a machine that can turn in place. For most applications, the vehicle is not intended to skid sideways on its wheels, significantly limiting the controllable degrees of freedom.
(Liang) Some robots have dual-Ackermann steering where both the front wheels and rear wheels can be steered, sometimes independently. Perhaps an extended version of the API should allow two input steering angles.
(Cedric) I think this goes beyond the intended scope of what is usually considered with the Ackermann geometry. However, if we want to be generic, my experience with space rover (6 independently steered wheels) suggest that the most generic representation is the velocity of the rover center and the position of the instantaneous center of rotation (IRC). The representations behaves even nicer if the IRC position is represented in polar coordinate as (theta,1/r). This nicely represent the "normal" Ackermann geometry up to crabbing (i.e. all wheel parallel but not aligned with the robot). Once the IRC gets inside the rover body, then we can even represent all kinds of rotation on the spot, but then 1/r is not nicely behaved. If the goal of this discussion is to focus on cars and bikes, I don't think there is a big advantage with going towards (v,thetaIRC,1/rIRC). Otherwise, algorithms that can work with this representation will also work for a car.
(Liang) Computing the steering angle from the IRC is too complex and also requires a standard coordinate frame. Perhaps we should create multiple levels of APIs. On the lowest level, for a single-ackermann chassis, the parameters would be velocity, steering angle, velocity acceleration and steering angle acceleration. Above that would be a higher-level API that accepts velocity and IRC parameters. The upper-level component would translate the IRC parameter into steering angle command(s).
(Cédric) if you don't have a mechanical linkage between each side, the computing real steering from virtual steering is not easier than computing it from the IRC.
(Liang) What is a virtual steering angle?
(Cédric) For a car-like robot, the left and right front wheel are in general not steered by the same amount (in order to make sure that the IRC is uniquely defined). However, in order to limit the number of command, people normally give as input the steering angle corresponding to a virtual wheel located at the center of the front axle. If the steering wheels are steered by independent motors, the individual steerings must be computed from the steering of the virtual wheel. If there is a mechanical linkage between the wheels (as in a real car), then this takes care of moving the steering units appropriately. HTH.
(Jack) I am not familiar with vehicles using exotic steering mechanisms. This is an interesting discussion, and I am not opposed to a more general solution than virtual steering angle. However, our current project involves only basic front-wheel Ackermann steering.
(Liang) Thanks. I agree our API should provide a single virtual steering angle rather than two actual steering angles. Then the question is: should our API use IRC or the virtual steering angle? I'm still a little wary about using IRC because it requires a coordinate frame external to the robot. Also, when I want to, say, steer the robot right at 2 degs, specifying this using an IRC location seams a bit counter-intuitive. Thoughts? Can the API provide both options?
(Cedric) The IRC does not require a coordinate frame external to the robot. It is defined in the coordinate frame attached to the robot. However, I agree that if we're just dealing with car-like system, it's a tedious way to define the steering angle. Maybe we should focus on that for now, and wait to see if there is a real need to go for something more generic. I'm always cautious about over-designing...
(Liang) Sounds good. Let's initially use a virtual steering angle and target car-like robots, leaving making things more generic as future work.
(Jack) Although the term is new to me, virtual steering angle is what we currently use, implying the "bicycle" (or "tricycle") model of steering. It is the average angle of the front wheels, in radians (left is positive).
(Cedric) Just to be pedantic here (and because we don't know who will read this statement), the average is actually an approximation as the real function would be non-linear. In practice, the error is within a couple of percents for the standard dimensions of a car, which is negligible given the other sources of errors...
(Jack) You are right. Thanks for the correction.
(Piyush) A standard interface for differential drive and holonomic robots typically takes in geometry_msgs/Twist. Is this the best solution for Ackermann robots as well?
(Jack) I think not. Steering angle is important. Although it is theoretically possible to compute that from velocity and yaw rate using some trigonometry, there are significant practical problems. When the vehicle accelerates, the changing velocity mandates a changing yaw rate to model a constant steering angle.
(Liang) The semantics of yaw rate and steering angle are clearly different. However, the number of parameters and their data types are likely the same. We could use the same geometry_msgs/Twist, but simply interpret the 'angular' parameter to mean steering angle.
(Cédric) please let's not start having message with a semantic inconsistent with its member names. It's barely ok for a quick hack, so a definitive no for a API specification discussion.
(Liang) Sounds good. We'll create a new message.
(Jack) Agreed. For reference (not a specific proposal), the messages we currently use are art_msgs/CarDrive and art_msgs/CarDriveStamped. The Gear and PilotBehavior are probably irrelevant to this discussion.
(Piyush) +1
(Piyush) From the above discussion it seems we are agreed on developing a new message. I will try to put together a draft of the design up somewhere.
(Liang) The art_msgs/CarDrive and art_msgs/CarDriveStamped messages seem like a good place to start. My main concern is they combine the motion command with the transmission setting making it possible for a user to create nonsensical messages like "speed = 2.0 and gear = Park". In addition, the transmission setting will infrequently change relative to the motion command so it does not make sense to send the transmission setting in each message. Thus, we should split it into a "CarDriveCmdMsg" and a "CarTransmissionSettingMsg". The CarDriveCmdMsg message specifies the virtual steering angle, speed (non-negative), various accelerations, and various jerks. The CarTransmissionSettingMsg selects the transmission setting (Park, Reverse, or Drive --- can we assume automatic transmission?). To move the car, the application simply publishes a CarTransmissionSettingMsg message followed by a sequence of many CarDriveCmdMsg messages.
(Jack) The transmission gear setting is too device-specific for a generic message. Let's just leave it out. A negative speed for driving in reverse is sufficient for car-like navigation.
(Liang) +1.
(Liang) What are the "knobs" that should be provided by a reference implementation? By "knobs" I mean the constant parameters like wheel base that allow the implementation to work with a range of Ackermann-based robots. Perhaps other knobs include the limits (e.g., max/min speed/steering angle) and accuracy (e.g., minimum distance of travel) of the robot.
(Jack) Good point. These are definitely things a generic Ackermann navigator needs to know. Since they are generally static, they could be parameters for the navigator.
(Jack) We should specify that a steering angle beyond the mechanical limits of the vehicle will be interpreted as the relevant positive or negative limit, instead.
(Liang) +1. Same for the speed parameter. Plus warning should be issued whenever the command is clipped.
(Austin) Knowing the minimum turning radius is critical for proper path-planning. Acceleration, braking and the radius/speed relationship when turning are also important, but depend heavily on terrain. Acceleration and braking torque curves are probably more useful in the general case.
(Liang) Isn't the minimum turning radius also dependent on the terrain? For example, wouldn't a robot operating on loose sand have a larger turning radius than an identical robot operating on solid asphalt? I agree that acceleration and braking curves would be more useful generally. Is there a standard data type through which these curves are specified?
(Piyush) This discussion has gotten fairly long. Based on this discussion, I have put forth 2 sample message formats in the next section. As we continue the discussion, we can modify these formats (and possibly merge them). I apologize for the names, any suggestions?
(Piyush) Ideally, I am not averse to having multiple formats as long as we can unify them in some way
(Austin) Now that we have a common message type, I think we should standardize on a common topic name. For holonomic robots, this is usually cmd_vel, but I think we should pick a new topic name.
(Austin) If someone ever wants to write a node that converts from Twist to AckermannDrive, it will require a differently named topics.
(Austin) We should choose a new topic name to help avoid confusion with existing base control messages on cmd_vel, since they will have incompatible types.
(Austin) I propose that the new topic be called ackermann_vel
(Jack) +1 for a standard topic name. While ackermann_vel is fine, I suggest ackermann_drive. I think we should definitely provide a node or nodelet that converts geometry_msgs/Twist to ackermann_msgs/AckermanDrive and geometry_msgs/TwistStamped to ackermann_msgs/AckermanDriveStamped.
(Piyush) I somehow prefer having cmd as a prefix or suffix to indicate it is a command. How about ackermann_cmd or ackermann_cmd_vel?
(Liang) +1 for ackermann_cmd since the message contains more than just velocity and there are no other types of ackermann commands we would send to the robot.
(Jack) +1; ackermann_cmd is good.
(Austin) +1 for ackermann_cmd
Proposed message formats
ackermann_msgs/SimpleControl
# Average angle of the front wheels, in radians (left is positive). This angle is an approximation of the true turning angle of the car float32 virtual_angle # Speed of the center of the rear axle (reverse is negative) float32 forward_speed
ackermann_msgs/ComplexControl
# Average angle of the front wheels, in radians (left is positive). This angle is an approximation of the true turning angle of the car float32 virtual_angle # Desired rate of change of the virtual angle float32 angular_velocity # Desired rate of change of angular_velocity. Humans can feel changes in while in a car float32 angular_acceleration # Speed of the center of the rear axle (reverse is negative) float32 forward_speed # Acceleration of the center of the rear axle float32 forward_acceleration # Jerk of the center of the rear axle float32 forward_jerk
(Cedric) Should we prefix the name of the jerk/acceleration and angular_velocity/acceleration with max_? If I understood the remaining of the discussion correctly, they are maximum desired values that the controller is allowed to use to reach the set point (forward_speed/virtual_angle).
(Jack) +1; forward_acceleration and forward_jerk are confusing names. The actual acceleration and jerk may be positive or negative and may apply to forward or backward motion. The values provided are both absolute value maxima and recommendations.
(Liang) I actually think the prefix should be "target_". This is because we are only providing general guidelines of what we want the robot to do. It is entirely possible for the robot to overshoot and exceed our guideline, though hopefully this only happens for a brief period of time.
(Cedric) I would name the virtual_angle "steering_angle" (after all, it is virtual for a car, but nor for a bike/tricycle).
(Jack) +1 for steering_angle.
(Liang) I vote for 'target_steering_angle'
(Jack) I think these messages should go in the nav_msgs package, not a new ackermann_msgs, and I prefer CarDrive and CarDriveStamped for the message names. I do like having versions with and without the time stamp.
(Liang) +1
(Piyush) Is CarDrive generic enough, given that we follow the bicycle model?
(Jack) Given the scope of this discussion, AckermannDrive would be more general.
(Piyushk) +1
(Jack) I don't see any need for a "simple" version of the message. All the additional fields will default to zero. If the sender does not fill them in, the semantics are the same. If the receiver ignores them, the results are the same.
(Liang) Can an efficiency argument be made for having a simple message? Wouldn't it significantly reduce the number of bytes transmitted between publisher and subscriber?
(Jack) These are small messages. Given the overhead of sending any message at all, I don't believe a few extra float values will have a measurable effect. I am more concerned about the complexity and confusion of drivers and navigators needing to support both message formats.
(Austin) For my platform, where my low-level controller only has 8k of RAM and somewhat limited bandwidth to the main computer, keeping messages relatively small is important. From experience, geometry_msgs/Twist is on the big side, but feasible. nav_msgs/Odometry, at 700+ bytes, is not.
(Jack) A valid point, but would you even want a float interface for that? For serial commands to a low-level device, I'd use a custom message. The generic AckermannDrive can be converted by a driver node running on the main computer to a smaller integer message for a custom micro-controller. What we are discussing now is a general message for multiple navigators and controller nodes.
(Jack) I don't see a need for angular_acceleration. I could see adding steering_angle_velocity for steering using clothoids, though I doubt many navigation nodes would use it. As usual, we could define zero to mean "as quickly as you want".
(Liang) +1 The API should allow the user to specify how quickly he wants the robot to change the steering angle. The name steering_angle_velocity describes this quite well.
(Jack) I can see the point of forward_speed, emphasizing the idea that negative values represent backward motion; but I still prefer speed.
(Liang) +1 for removing forward_. However, I'm currently in favor of using target_speed because it explicitly defines it to be a target. I'm OK with removing `target_' if we specify in the comments that it is a target.
(Jack) The units of each field need to be specified: radians, radians/s, m/s, m/s2 m/s3.
(Liang) We should make it very clear in the comments that the speed and steering angle are only general guidelines, that they simply express the desires of the user, and that the robot is free to voilate them in either direction.
(Jack) +1, though preferably not much greater in magnitude.
(Piyush) I think there are a couple of issues being discussed, but I will update the message once more to version 3 below. I have marked this as the current draft.
nav_msgs/AckermannDrive
# Average angle of the front wheels in radians (left is positive). This angle is the true turning angle for bicycles and motorcycles. It is an approximation for a car, computed by taking the average of the angles of the 2 front wheels. float32 steering_angle # Desired rate of change of the steering angle in radians/second. float32 steering_angle_velocity # Speed of the center of the rear axle in meters/second (reverse is negative) float32 speed # Desired acceleration of the center of the rear axle in meters/second^2 float32 acceleration # Desired jerk of the center of the rear axle in meters/second^3 float32 jerk
(Liang) Let's remove the max_ prefix and make implicit the fact that the fields only indicate the desires of the publisher. This conforms to the semantics of geometry_msgs/Twist, which does not use a prefix. In addition, max_ implies that any sustained value less than the specified value is OK, which is not true. A better prefix would be desired_, though this is too verbose, which is why we should simply omit it. Let's just make it clear using comments that all fields are desired values, i.e., modify the comment for steering_angle to be "Desired steering angle..." and the comment for speed to be "Desired speed..."
(Jack) +1
(Piyush) +1; with 3 votes, I have updated the message in place
(Liang) Another message we should create is an Ackermann-specific odometry message (perhaps nav_msgs/AckermannOdometry). The existing odometry message, nav_msgs/Odometry, is specific to differential drive robots, e.g., the position field indicates the center of the robot whereas we want it to indicate the location of the center of the robot's rear axle (please correct me if I'm wrong).
(Jack) nav_msgs/Odometry works fine as long as the frame_id specified in its Header is defined appropriately. We use "/vehicle" instead of "/base_link", and define it to be the point on the ground immediately below the center of the rear axle.
(Liang) OK.
(Liang) We should also define a message published by the driver that indicates the properties of the robot. This refers back to the "knobs" discussed above. The message (perhaps nav_msgs/AckermannProps) would contain the wheel base, turning radius, and various limits, among other things, which will be used by, for example, path planning nodes.
(Jack) I was imagining these to be relatively static, and hence appropriate for ROS parameters. Maybe there are cases where they need to change. Can you think of a scenario like that?
(Liang) This is just theoretical, but maybe the maximum speed of the robot will decrease as the battery runs low, or the minimum turning radius will increase when the robot moves from asphalt to sand. I can imagine certain robots being able to extend/shrink its wheel base (kind of like the HIRIKO Project at MIT). These are definitely exceptional situations, so we can leave it as future work.
(Piyush) We can add to the comments that the driver will try and follow these limits within its own capabilities. However what value does the controller provide for acceleration, jerk etc when it does not want these limits?
(Liang) How about let's make zero mean "unlimited"?
(Jack) +1. Another option, currently popular in the ROS community, is numeric_limits::infinity(), but I prefer zero because that is the default value for message constructors and it has no other meaningful interpretation.
(Ken): I was asked for an opinion on where to house these. With the advent of unary stacks, as well as the catkin-build system for Fuerte that we are using for std_msgs/common_msgs, I'd vote that they just be by themselves. I say this for two reasons:
- From a release management perspective, it gives the Ackermann Group the greatest control over release iterations. For discovery, it would be fine to note on the common_msgs wiki page that there is a separate ackermann ontology.
- If you want to be able to use the ackermann messages in Electric or earlier code, it can't be part of common_msgs in those distributions. Thus, keeping the messages separate simplifies the configuration management.
(Jack) +1. I asked Ken for his view on packaging, because I was beginning to doubt my earlier recommendation that it go in nav_msgs. He has a broader view of how various ROS components should fit together. We can host a new ackermann stack with an ackermann_msgs package on the utexas-art-ros-pkg repository, or use one of several other options (kforge.ros.org, googlecode, github, etc.).
(Jack) to minimize its dependencies, I am packaging ackermann_msgs by itself as a unary stack.
(Piyush) For the moment, I would prefer placing it on an existing repository. Once we have enough developed code to move beyond experimental and the stack is ready to use, we can move the code to an independent repository. SVN is nice for partial checkouts; +1 on using utexas-art-ros-pkg.
(Liang) +1 for utexas-art-ros-pkg. I assume we'll have a stamped and non-stamped version.
(Jack) Yes. The unstamped message is good for inclusion in other messages or data structures. The stamped one is better for actual commands.
Conclusion
The ackermann_msgs package defines the ackermann_msgs/AckermannDrive and ackermann_msgs/AckermannDriveStamped messages. Contact Piyush or Jack with your Google login to be registered as a utexas-art-ros-pkg developer.
I have added comments prompted by this discussion. Since the wiki indexer is running behind right now, here is the current ackermann_msgs/AckermannDrive definition for reference. The new messages are now on the wiki, please refer to those versions for further review.
Now that the ackermann_msgs package exists, I created a review page in the standard place, referring back to this discussion.