sub: GCS_Mavlink: fix depth hold typemask bug

This commit is contained in:
ES-Alexander 2022-05-03 12:05:48 +10:00 committed by Willian Galvani
parent 6bfaa3ef62
commit 21cd4f1976
2 changed files with 3 additions and 1 deletions

View File

@ -660,6 +660,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
break;
}
bool z_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE;
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
@ -671,7 +672,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
*/
if (!pos_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD
if (!z_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD
sub.pos_control.set_pos_target_z_cm(packet.alt*100);
break;
}

View File

@ -186,6 +186,7 @@ enum LoggingParameters {
#define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000
// for mavlink SET_POSITION_TARGET messages
#define MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE (1<<2)
#define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))
#define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))
#define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))