Skip to content

Commit

Permalink
Update message definitions Wed Sep 25 08:22:05 UTC 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Sep 25, 2024
1 parent ba3ebfd commit 2f6b65d
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 0 deletions.
7 changes: 7 additions & 0 deletions msg/RoverMecanumGuidanceStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
uint64 timestamp # time since system start (microseconds)

float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error # [rad] Heading error of the pure pursuit controller
float32 desired_speed # [m/s] Desired velocity magnitude (speed)

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

float32 forward_speed_setpoint # [m/s] Desired forward speed
float32 forward_speed_setpoint_normalized # [-1, 1] Desired normalized forward speed
float32 lateral_speed_setpoint # [m/s] Desired lateral speed
float32 lateral_speed_setpoint_normalized # [-1, 1] Desired normalized lateral speed
float32 yaw_rate_setpoint # [rad/s] Desired yaw rate
float32 yaw_rate_setpoint_normalized # [-1, 1] Desired normalized yaw rate
float32 yaw_setpoint # [rad] Desired yaw (heading)

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

float32 measured_forward_speed # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards
float32 measured_lateral_speed # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left
float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint output of the closed loop yaw controller
float32 measured_yaw_rate # [rad/s] Measured yaw rate
float32 measured_yaw # [rad] Measured yaw
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller
float32 pid_forward_throttle_integral # Integral of the PID for the closed loop forward speed controller
float32 pid_lateral_throttle_integral # Integral of the PID for the closed loop lateral speed controller

# TOPICS rover_mecanum_status

0 comments on commit 2f6b65d

Please sign in to comment.