PX4-Autopilot/msg/VehicleRatesSetpoint.msg
Daniel Agar 9ee8fa21cd
PX4 ROS2 msg conformity and explicit topics
- .msg files are PascalCase
 - topics are still either per msg or explicitly listed in TOPICS
 - compatible structs are still generated (eg struct msg_s), but ROS2 style px4::msg::Msg is also available
2022-03-07 10:36:27 -05:00

10 lines
503 B
Plaintext

uint64 timestamp # time since system start (microseconds)
float32 roll # body angular rates in NED frame
float32 pitch # body angular rates in NED frame
float32 yaw # body angular rates in NED frame
# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand.
# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero.
float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1]