mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Camera: rely on AHRS for position, not GPS
our location may not be coming from a GPS
This commit is contained in:
parent
b65a5a904c
commit
bc80358e9b
@ -6,7 +6,6 @@
|
|||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
|
||||||
#include "AP_Camera_Backend.h"
|
#include "AP_Camera_Backend.h"
|
||||||
#include "AP_Camera_Servo.h"
|
#include "AP_Camera_Servo.h"
|
||||||
#include "AP_Camera_Relay.h"
|
#include "AP_Camera_Relay.h"
|
||||||
|
@ -1,9 +1,13 @@
|
|||||||
#include "AP_Camera_Backend.h"
|
#include "AP_Camera_config.h"
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
|
|
||||||
|
#include "AP_Camera_Backend.h"
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -57,8 +61,10 @@ void AP_Camera_Backend::update()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check GPS status
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
|
||||||
|
Location current_loc;
|
||||||
|
if (!ahrs.get_location(current_loc)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -68,15 +74,10 @@ void AP_Camera_Backend::update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check vehicle roll angle is less than configured maximum
|
// check vehicle roll angle is less than configured maximum
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
if ((_frontend.get_roll_max() > 0) && (fabsf(ahrs.roll_sensor * 1e-2f) > _frontend.get_roll_max())) {
|
||||||
if ((_frontend.get_roll_max() > 0) && (fabsf(AP::ahrs().roll_sensor * 1e-2f) > _frontend.get_roll_max())) {
|
|
||||||
return;
|
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
|
// initialise last location to current location
|
||||||
if (last_location.lat == 0 && last_location.lng == 0) {
|
if (last_location.lat == 0 && last_location.lng == 0) {
|
||||||
last_location = current_loc;
|
last_location = current_loc;
|
||||||
|
Loading…
Reference in New Issue
Block a user