|
|
|
@ -1719,12 +1719,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
@@ -1719,12 +1719,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_VISION_POSITION_DELTA: |
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED |
|
|
|
|
copter.g2.visual_odom.handle_msg(msg); |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if TOY_MODE_ENABLED == ENABLED |
|
|
|
|
case MAVLINK_MSG_ID_NAMED_VALUE_INT: |
|
|
|
|
copter.g2.toy_mode.handle_message(msg); |
|
|
|
@ -1842,6 +1836,16 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
@@ -1842,6 +1836,16 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
|
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_VisualOdom *GCS_MAVLINK_Copter::get_visual_odom() const |
|
|
|
|
{ |
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED |
|
|
|
|
return &copter.g2.visual_odom; |
|
|
|
|
#else |
|
|
|
|
return nullptr; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) { |
|
|
|
|
MAV_RESULT result = MAV_RESULT_FAILED; |
|
|
|
|
|
|
|
|
|