|
|
|
@ -1359,10 +1359,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
@@ -1359,10 +1359,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
rover.g2.proximity.handle_msg(msg); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_VISION_POSITION_DELTA: |
|
|
|
|
rover.g2.visual_odom.handle_msg(msg); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
handle_common_message(msg); |
|
|
|
|
break; |
|
|
|
@ -1469,6 +1465,15 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Rover::get_advanced_failsafe() const
@@ -1469,6 +1465,15 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Rover::get_advanced_failsafe() const
|
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const |
|
|
|
|
{ |
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED |
|
|
|
|
return &rover.g2.visual_odom; |
|
|
|
|
#else |
|
|
|
|
return nullptr; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
Compass *GCS_MAVLINK_Rover::get_compass() const |
|
|
|
|
{ |
|
|
|
|
return &rover.compass; |
|
|
|
|