Skip to content

Commit

Permalink
AP_Camera: rely on AHRS for position, not GPS
Browse files Browse the repository at this point in the history
our location may not be coming from a GPS
  • Loading branch information
peterbarker committed Jul 31, 2024
1 parent 5f40319 commit 8f74462
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 10 deletions.
1 change: 0 additions & 1 deletion libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_GPS/AP_GPS.h>
#include "AP_Camera_Backend.h"
#include "AP_Camera_Servo.h"
#include "AP_Camera_Relay.h"
Expand Down
20 changes: 11 additions & 9 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
#include "AP_Camera_Backend.h"
#include "AP_Camera_config.h"

#if AP_CAMERA_ENABLED

#include "AP_Camera_Backend.h"

#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Mount/AP_Mount.h>
#include <AP_AHRS/AP_AHRS.h>

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -57,8 +61,11 @@ void AP_Camera_Backend::update()
return;
}

// check GPS status
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
Location current_loc;
const AP_AHRS &ahrs = AP::ahrs();
if (!ahrs.get_location(current_loc)) {
last_location.lat = 0;
last_location.lng = 0;
return;
}

Expand All @@ -68,15 +75,10 @@ void AP_Camera_Backend::update()
}

// check vehicle roll angle is less than configured maximum
const AP_AHRS &ahrs = AP::ahrs();
if ((_frontend.get_roll_max() > 0) && (fabsf(AP::ahrs().roll_sensor * 1e-2f) > _frontend.get_roll_max())) {
if ((_frontend.get_roll_max() > 0) && (fabsf(ahrs.roll_sensor * 1e-2f) > _frontend.get_roll_max())) {
return;
}

// get current location. ignore failure because AHRS will provide its best guess
Location current_loc;
IGNORE_RETURN(ahrs.get_location(current_loc));

// initialise last location to current location
if (last_location.lat == 0 && last_location.lng == 0) {
last_location = current_loc;
Expand Down

0 comments on commit 8f74462

Please sign in to comment.