AP_Camera: use AP_AHRS singleton to get current location and home

This commit is contained in:
Peter Barker 2019-03-26 22:06:18 +11:00 committed by Andrew Tridgell
parent 1adec017a2
commit 8ce4a1fce7
3 changed files with 17 additions and 3 deletions

View File

@ -321,6 +321,10 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
void AP_Camera::send_feedback(mavlink_channel_t chan) const
{
const AP_AHRS &ahrs = AP::ahrs();
Location current_loc;
if (!ahrs.get_position(current_loc)) {
// completely ignore this failure! AHRS will provide its best guess.
}
float altitude, altitude_rel;
if (current_loc.relative_alt) {
@ -358,6 +362,13 @@ void AP_Camera::update()
_last_location.lng = 0;
return;
}
const AP_AHRS &ahrs = AP::ahrs();
Location current_loc;
if (!ahrs.get_position(current_loc)) {
// completely ignore this failure! AHRS will provide its best guess.
}
if (_last_location.lat == 0 && _last_location.lng == 0) {
_last_location = current_loc;
return;

View File

@ -18,9 +18,8 @@
class AP_Camera {
public:
AP_Camera(uint32_t _log_camera_bit, const struct Location &_loc)
AP_Camera(uint32_t _log_camera_bit)
: log_camera_bit(_log_camera_bit)
, current_loc(_loc)
{
AP_Param::setup_object_defaults(this, var_info);
_singleton = this;
@ -130,7 +129,6 @@ private:
void Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us=0);
uint32_t log_camera_bit;
const struct Location &current_loc;
// update camera trigger - 50Hz
void update_trigger();

View File

@ -6,6 +6,11 @@ void AP_Camera::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us)
{
const AP_AHRS &ahrs = AP::ahrs();
Location current_loc;
if (!ahrs.get_position(current_loc)) {
// completely ignore this failure! AHRS will provide its best guess.
}
int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;