PX4-Autopilot/msg/offboard_control_mode.msg
pedro-roque a707403eaf mc_att_ctrl: added yawrate control from offboard.
This commit adds Roll Pitch Yawrate Thrust (RPYrT) setpoint control to the
PX4 stack, enabling the UAV to follow specific yawrates sent from
offboard. It also introduces individual body_rate flags, along the
lines of mavros.

Tested on a MoCap enabled flight arena in KTH Royal Institute of
Technology, Stockholm. The MAV receives RPYrT setpoints from an
external PID controller to stabilize around position setpoints.
The UAV is also externally disturbed to assess the stability to
external unmodeled events.

Fixed Kabir comments.

Removed deprecated ignore_bodyrate.

Fixed integration test.
2019-06-04 08:26:09 +02:00

14 lines
289 B
Plaintext

# Off-board control mode
uint64 timestamp # time since system start (microseconds)
bool ignore_thrust
bool ignore_attitude
bool ignore_bodyrate_x
bool ignore_bodyrate_y
bool ignore_bodyrate_z
bool ignore_position
bool ignore_velocity
bool ignore_acceleration_force
bool ignore_alt_hold