Skip to content

Commit 9825a7a

Browse files
committed
Update PX4 Firmware metadata Wed Jul 9 07:03:10 UTC 2025
1 parent 4d8b160 commit 9825a7a

19 files changed

+77
-69
lines changed

en/msg_docs/PurePursuitStatus.md

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,17 @@
11
# PurePursuitStatus (UORB message)
22

3-
3+
Pure pursuit status
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PurePursuitStatus.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Pure pursuit status
99

10-
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
11-
float32 target_bearing # [rad] Target bearing calculated by the pure pursuit controller
12-
float32 crosstrack_error # [m] Shortest distance from the vehicle to the path (Positiv: Vehicle is on the right hand side with respect to the oriented path vector, Negativ: Left of the path)
13-
float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint
14-
float32 bearing_to_waypoint # [rad] Bearing towards current waypoint
10+
uint64 timestamp # [us] Time since system start
11+
float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller
12+
float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller
13+
float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path
14+
float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint
15+
float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint
1516

1617
```
Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
# RoverAttitudeSetpoint (UORB message)
22

3-
3+
Rover Attitude Setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeSetpoint.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Attitude Setpoint
99

10-
float32 yaw_setpoint # [rad] Expressed in NED frame
10+
uint64 timestamp # [us] Time since system start
11+
float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint
1112

1213
```

en/msg_docs/RoverAttitudeStatus.md

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,14 @@
11
# RoverAttitudeStatus (UORB message)
22

3-
3+
Rover Attitude Status
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeStatus.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Attitude Status
99

10-
float32 measured_yaw # [rad/s] Measured yaw rate
11-
float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates)
10+
uint64 timestamp # [us] Time since system start
11+
float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw
12+
float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates)
1213

1314
```
Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,17 @@
11
# RoverPositionSetpoint (UORB message)
22

3-
3+
Rover Position Setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
9-
10-
float32[2] position_ned # 2-dimensional position setpoint in NED frame [m]
11-
float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position)
12-
float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed)
13-
float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero)
8+
# Rover Position Setpoint
149

15-
float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw)
10+
uint64 timestamp # [us] Time since system start
11+
float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position
12+
float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track
13+
float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed
14+
float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with
15+
float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel
1616

1717
```

en/msg_docs/RoverRateSetpoint.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
# RoverRateSetpoint (UORB message)
22

3-
3+
Rover Rate setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateSetpoint.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Rate setpoint
99

10-
float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame
10+
uint64 timestamp # [us] Time since system start
11+
float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint
1112

1213
```

en/msg_docs/RoverRateStatus.md

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,15 @@
11
# RoverRateStatus (UORB message)
22

3-
3+
Rover Rate Status
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateStatus.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Rate Status
99

10-
float32 measured_yaw_rate # [rad/s] Measured yaw rate
11-
float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates)
12-
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
10+
uint64 timestamp # [us] Time since system start
11+
float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate
12+
float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates)
13+
float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller
1314

1415
```
Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
# RoverSteeringSetpoint (UORB message)
22

3-
3+
Rover Steering setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSteeringSetpoint.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Steering setpoint
99

10-
float32 normalized_steering_setpoint # [-1, 1] Positiv = Turn right, Negativ: Turn left (Ackermann: Steering angle, Differential/Mecanum: Speed difference between the left and right wheels)
10+
uint64 timestamp # [us] Time since system start
11+
float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels
1112

1213
```
Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
# RoverThrottleSetpoint (UORB message)
22

3-
3+
Rover Throttle setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverThrottleSetpoint.msg)
66

77
```c
8+
# Rover Throttle setpoint
89

9-
uint64 timestamp # time since system start (microseconds)
10-
11-
float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards)
12-
float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left)
10+
uint64 timestamp # [us] Time since system start
11+
float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis
12+
float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis
1313

1414
```
Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,15 @@
11
# RoverVelocitySetpoint (UORB message)
22

3-
3+
Rover Velocity Setpoint
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Velocity Setpoint
99

10-
float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative)
11-
float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction]
12-
float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame
10+
uint64 timestamp # [us] Time since system start
11+
float32 speed # [m/s] [@range -inf (Backwards), inf (Forwards)] Speed setpoint
12+
float32 bearing # [rad] [@range -pi,pi] [@frame NED] [@invalid: NaN, speed is defined in body x direction] Bearing setpoint
13+
float32 yaw # [rad] [@range -pi, pi] [@frame NED] [@invalid NaN, Defaults to vehicle yaw] Mecanum only: Yaw setpoint
1314

1415
```

en/msg_docs/RoverVelocityStatus.md

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,18 @@
11
# RoverVelocityStatus (UORB message)
22

3-
3+
Rover Velocity Status
44

55
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocityStatus.msg)
66

77
```c
8-
uint64 timestamp # time since system start (microseconds)
8+
# Rover Velocity Status
99

10-
float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards
11-
float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards
12-
float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction
13-
float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only)
14-
float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only)
15-
float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only)
10+
uint64 timestamp # [us] Time since system start
11+
float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction
12+
float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates)
13+
float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction
14+
float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction
15+
float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates)
16+
float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction
1617

1718
```

0 commit comments

Comments
 (0)