mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Sub: Add maneuver/attitude stick mode indicator msg
This commit is contained in:
parent
b8430ceaa5
commit
a75a5c5a0b
@ -431,6 +431,13 @@ bool NOINLINE Sub::send_info(mavlink_channel_t chan)
|
||||
"InputHold",
|
||||
input_hold_engaged);
|
||||
|
||||
CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
|
||||
mavlink_msg_named_value_float_send(
|
||||
chan,
|
||||
AP_HAL::millis(),
|
||||
"StickMode",
|
||||
roll_pitch_flag);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -336,6 +336,9 @@ private:
|
||||
// Flag indicating if we are currently using input hold
|
||||
bool input_hold_engaged;
|
||||
|
||||
// Flag indicating current stick mode: Maneuver/Attitude
|
||||
uint16_t roll_pitch_flag;
|
||||
|
||||
// 3D Location vectors
|
||||
// Current location of the Sub (altitude is relative to home)
|
||||
Location_Class current_loc;
|
||||
|
@ -22,8 +22,6 @@ uint16_t buttons_prev;
|
||||
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
|
||||
}
|
||||
|
||||
void Sub::init_joystick()
|
||||
|
Loading…
Reference in New Issue
Block a user