Copter: GCSMavlink Guided inputs check force_set and reject

This commit is contained in:
Josh Henderson 2021-09-13 04:41:43 -04:00 committed by Randy Mackay
parent 0f8bcbf4b8
commit 483d308781

View File

@ -1009,6 +1009,8 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
POSITION_TARGET_TYPEMASK_YAW_IGNORE;
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE =
POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_FORCE_SET =
POSITION_TARGET_TYPEMASK_FORCE_SET;
switch (msg.msgid) {
@ -1119,6 +1121,12 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;
// force_set true, do not accept command
if (force_set) {
break;
}
// prepare position
Vector3f pos_vector;
@ -1207,6 +1215,12 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;
// force_set true, do not accept command
if (force_set) {
break;
}
// extract location from message
Location loc;