Browse Source

GCS_MAVLink: use visual odometry singleton

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
63427629e1
  1. 1
      libraries/GCS_MAVLink/GCS.h
  2. 3
      libraries/GCS_MAVLink/GCS_Common.cpp

1
libraries/GCS_MAVLink/GCS.h

@ -291,7 +291,6 @@ protected: @@ -291,7 +291,6 @@ protected:
// enforcement of GCS sysid
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg);
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }
virtual bool set_mode(uint8_t mode) = 0;
void set_ekf_origin(const Location& loc);

3
libraries/GCS_MAVLink/GCS_Common.cpp

@ -24,6 +24,7 @@ @@ -24,6 +24,7 @@
#include <AP_BLHeli/AP_BLHeli.h>
#include <AP_Common/Semaphore.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include "GCS.h"
@ -2772,7 +2773,7 @@ void GCS_MAVLINK::handle_data_packet(mavlink_message_t *msg) @@ -2772,7 +2773,7 @@ void GCS_MAVLINK::handle_data_packet(mavlink_message_t *msg)
void GCS_MAVLINK::handle_vision_position_delta(mavlink_message_t *msg)
{
AP_VisualOdom *visual_odom = get_visual_odom();
AP_VisualOdom *visual_odom = AP::visualodom();
if (visual_odom == nullptr) {
return;
}

Loading…
Cancel
Save