|
|
|
@ -945,6 +945,27 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
@@ -945,6 +945,27 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
|
|
|
|
|
|
|
|
|
|
void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) |
|
|
|
|
{ |
|
|
|
|
// for mavlink SET_POSITION_TARGET messages
|
|
|
|
|
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE = |
|
|
|
|
POSITION_TARGET_TYPEMASK_X_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_Y_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_Z_IGNORE; |
|
|
|
|
|
|
|
|
|
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE = |
|
|
|
|
POSITION_TARGET_TYPEMASK_VX_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_VY_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_VZ_IGNORE; |
|
|
|
|
|
|
|
|
|
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE = |
|
|
|
|
POSITION_TARGET_TYPEMASK_AX_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_AY_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_AZ_IGNORE; |
|
|
|
|
|
|
|
|
|
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE = |
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE; |
|
|
|
|
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE = |
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; |
|
|
|
|
|
|
|
|
|
switch (msg.msgid) { |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT: // MAV ID: 0
|
|
|
|
|