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.
This commit is contained in:
pedro-roque
2019-05-23 15:24:12 +02:00
committed by Julian Oes
parent ac002db25c
commit a707403eaf
4 changed files with 18 additions and 17 deletions
@@ -129,7 +129,9 @@ class ManualInput(object):
mode = offboard_control_mode()
mode.ignore_thrust = ignore_thrust
mode.ignore_attitude = ignore_attitude
mode.ignore_bodyrate = ignore_bodyrate
mode.ignore_bodyrate_x = ignore_bodyrate
mode.ignore_bodyrate_y = ignore_bodyrate
mode.ignore_bodyrate_z = ignore_bodyrate
mode.ignore_position = ignore_position
mode.ignore_velocity = ignore_velocity
mode.ignore_acceleration_force = ignore_acceleration_force