CmdVel
Sends a 2D velocity command with forward speed and turning rate. The most common message type in mobile robotics — used between planners, controllers, and drive systems on differential drive, holonomic, and Ackermann platforms.
Python: Available via
horus.CmdVel(linear, angular). See Python Control Messages.ROS2 equivalent:
geometry_msgs/Twist(2D subset). HORUS uses a dedicated 2D type for the common case. Converts to/fromTwistautomatically.
// simplified
use horus::prelude::*;
Quick Reference — Fields
| Field | Type | Unit | Description |
|---|---|---|---|
linear | f32 | m/s | Forward velocity. Positive = forward, negative = backward |
angular | f32 | rad/s | Turning rate. Positive = counter-clockwise, negative = clockwise |
timestamp_ns | u64 | ns | Timestamp in nanoseconds since epoch |
Size: 16 bytes (u64 + f32 + f32). #[repr(C)] for zero-copy IPC.
Quick Reference — Methods
| Method | Returns | Description |
|---|---|---|
new(linear, angular) | CmdVel | Creates with current timestamp |
zero() | CmdVel | Creates zero velocity (stopped) |
with_timestamp(linear, angular, timestamp_ns) | CmdVel | Creates with explicit timestamp |
default() | CmdVel | Same as zero() |
Quick Reference — Conversions
| From | To | Mapping |
|---|---|---|
Twist | CmdVel | twist.linear[0] → linear, twist.angular[2] → angular (f64→f32) |
CmdVel | Twist | linear → twist.linear[0], angular → twist.angular[2] (f32→f64) |
Constructor Methods
new(linear, angular)
Creates a velocity command with the current timestamp.
Signature
// simplified
pub fn new(linear: f32, angular: f32) -> Self
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
linear | f32 | yes | Forward velocity in m/s. Positive = forward, negative = backward. |
angular | f32 | yes | Turning rate in rad/s. Positive = counter-clockwise, negative = clockwise. |
Returns
CmdVel — with timestamp_ns set to the current time via timestamp_now().
Panics
Never.
Example
// simplified
use horus::prelude::*;
// Drive forward at 0.5 m/s, turn left at 0.3 rad/s
let cmd = CmdVel::new(0.5, 0.3);
let topic: Topic<CmdVel> = Topic::new("cmd_vel")?;
topic.send(cmd);
zero()
Creates a zero velocity command (stopped).
Signature
// simplified
pub fn zero() -> Self
Parameters
None.
Returns
CmdVel — with linear = 0.0, angular = 0.0, and current timestamp.
When to use
- Shutdown sequences — always send zero velocity before the motor controller stops
- Emergency stop — override the current command with zero
- Idle state — robot should hold position
Example
// simplified
use horus::prelude::*;
// SAFETY: always send zero on shutdown to prevent runaway
fn shutdown(&mut self) -> Result<()> {
self.cmd_pub.send(CmdVel::zero());
Ok(())
}
with_timestamp(linear, angular, timestamp_ns)
Creates a velocity command with an explicit timestamp.
Signature
// simplified
pub fn with_timestamp(linear: f32, angular: f32, timestamp_ns: u64) -> Self
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
linear | f32 | yes | Forward velocity in m/s. |
angular | f32 | yes | Turning rate in rad/s. |
timestamp_ns | u64 | yes | Timestamp in nanoseconds since epoch. |
Returns
CmdVel — with the specified timestamp.
When to use
- Replay/recording systems where timestamps come from a log file
- Simulation with deterministic time
Python Constructor
Creates a velocity command from keyword arguments.
Signature
CmdVel(linear, angular, timestamp_ns=0)
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
linear | f32 | yes | Forward velocity in m/s |
angular | f32 | yes | Turning rate in rad/s |
timestamp_ns | u64 | no | Timestamp. Default: 0. |
Returns
CmdVel instance. Python also provides a class method CmdVel.zero().
The Python constructor defaults timestamp_ns to 0, while Rust's new() uses the current time. Set timestamp_ns explicitly if your pipeline depends on accurate timing.
Example
from horus import CmdVel, Topic
cmd = CmdVel(linear=0.5, angular=0.3)
topic = Topic(CmdVel)
topic.send(cmd)
# Stop the robot
topic.send(CmdVel.zero())
Safety Notes
Always send zero velocity on shutdown. Implement shutdown() (Rust) or the shutdown callback (Python) to send CmdVel::zero(). This prevents runaway if the controller crashes or loses connection.
- Clamp values — enforce maximum speed and turn rate before sending to hardware drivers
- Pair with E-stop — the Emergency Stop recipe overrides
cmd_velwhen triggered - Watchdog timeout — motor controllers should stop if no
CmdVelis received within a timeout (e.g., 100ms)
Common Patterns
Differential Drive Kinematics
Convert CmdVel to left/right wheel speeds:
// simplified
use horus::prelude::*;
fn to_wheel_speeds(cmd: &CmdVel, wheel_base: f32, wheel_radius: f32) -> (f32, f32) {
let left = (cmd.linear - cmd.angular * wheel_base / 2.0) / wheel_radius;
let right = (cmd.linear + cmd.angular * wheel_base / 2.0) / wheel_radius;
(left, right)
}
See the Differential Drive recipe for a complete example.
Clamped Teleop
// simplified
use horus::prelude::*;
fn clamp_cmd(cmd: CmdVel, max_linear: f32, max_angular: f32) -> CmdVel {
CmdVel::new(
cmd.linear.clamp(-max_linear, max_linear),
cmd.angular.clamp(-max_angular, max_angular),
)
}
See Also
- Control Messages (Rust) — Full Rust API for all control types
- Control Messages (Python) — Python control API
- Twist — Full 3D linear + angular velocity
- Odometry — Position feedback from wheel encoders
- Differential Drive Recipe — Mobile robot control
- Emergency Stop Recipe — Safety stop pattern