Skip to content

Commit

Permalink
Update message definitions Thu Oct 31 16:03:58 UTC 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Oct 31, 2024
1 parent d23220b commit 4b0b933
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 5 deletions.
2 changes: 0 additions & 2 deletions msg/RoverAckermannGuidanceStatus.msg
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
uint64 timestamp # time since system start (microseconds)

float32 desired_speed # [m/s] Rover desired ground speed
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error # [deg] Heading error of the pure pursuit controller
float32 pid_throttle_integral # [-1, 1] Integral of the PID for the normalized throttle to control the rover speed during missions

# TOPICS rover_ackermann_guidance_status
9 changes: 9 additions & 0 deletions msg/RoverAckermannSetpoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
uint64 timestamp # time since system start (microseconds)

float32 forward_speed_setpoint # [m/s] Desired speed in body x direction. Positiv: forwards, Negativ: backwards
float32 forward_speed_setpoint_normalized # [-1, 1] Desired normalized speed in body x direction. Positiv: forwards, Negativ: backwards
float32 steering_setpoint # [rad] Desired steering angle
float32 steering_setpoint_normalized # [-1, 1] Desired normalized steering angle
float32 lateral_acceleration_setpoint # [m/s^2] Desired acceleration in body y direction. Positiv: right, Negativ: left.

# TOPICS rover_ackermann_setpoint
10 changes: 7 additions & 3 deletions msg/RoverAckermannStatus.msg
Original file line number Diff line number Diff line change
@@ -1,7 +1,11 @@
uint64 timestamp # time since system start (microseconds)

float32 throttle_setpoint # [-1, 1] Normalized throttle setpoint
float32 steering_setpoint # [-1, 1] Normalized steering setpoint
float32 actual_speed # [m/s] Rover ground speed
float32 measured_forward_speed # [m/s] Measured speed in body x direction. Forwards: positiv, Backwards: negativ
float32 adjusted_forward_speed_setpoint # [m/s] Speed setpoint after applying slew rate
float32 steering_setpoint_normalized # [-1, 1] Normalized steering setpoint
float32 adjusted_steering_setpoint_normalized # [-1, 1] Normalized steering setpoint after applying slew rate
float32 measured_lateral_acceleration # [m/s^2] Measured acceleration in body y direction. Positiv: right, Negativ: left.
float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller
float32 pid_lat_accel_integral # Integral of the PID for the closed loop lateral acceleration controller

# TOPICS rover_ackermann_status

0 comments on commit 4b0b933

Please sign in to comment.