mirror of https://github.com/ArduPilot/ardupilot
Sub: send Roll/Pitch Toggle flag
This commit is contained in:
parent
544df71fd2
commit
ba415c99fe
|
@ -140,6 +140,9 @@ bool GCS_MAVLINK_Sub::send_info()
|
|||
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
|
||||
send_named_float("InputHold", sub.input_hold_engaged);
|
||||
|
||||
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
|
||||
send_named_float("RollPitch", sub.roll_pitch_flag);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -308,6 +308,9 @@ private:
|
|||
// Flag indicating if we are currently using input hold
|
||||
bool input_hold_engaged;
|
||||
|
||||
// Flag indicating if we are currently controlling Pitch and Roll instead of forward/lateral
|
||||
bool roll_pitch_flag = false;
|
||||
|
||||
// 3D Location vectors
|
||||
// Current location of the Sub (altitude is relative to home)
|
||||
Location current_loc;
|
||||
|
|
|
@ -24,7 +24,6 @@ const uint8_t SERVO_CHAN_1 = 9; // Pixhawk Aux1
|
|||
const uint8_t SERVO_CHAN_2 = 10; // Pixhawk Aux2
|
||||
const uint8_t SERVO_CHAN_3 = 11; // Pixhawk Aux3
|
||||
|
||||
uint8_t roll_pitch_flag = false; // Flag to adjust roll/pitch instead of forward/lateral
|
||||
bool controls_reset_since_input_hold = true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue