AP_Camera: use GPS singleton

This commit is contained in:
Peter Barker 2017-11-13 11:30:58 +11:00 committed by Francisco Ferreira
parent 0934bdb5dc
commit 7258fa81d9
2 changed files with 9 additions and 11 deletions

View File

@ -251,8 +251,9 @@ void AP_Camera::send_feedback(mavlink_channel_t chan)
altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
mavlink_msg_camera_feedback_send(chan,
gps.time_epoch_usec(),
mavlink_msg_camera_feedback_send(
chan,
AP::gps().time_epoch_usec(),
0, 0, _image_index,
current_loc.lat, current_loc.lng,
altitude*1e-2, altitude_rel*1e-2,
@ -265,7 +266,7 @@ void AP_Camera::send_feedback(mavlink_channel_t chan)
*/
void AP_Camera::update()
{
if (gps.status() < AP_GPS::GPS_OK_FIX_3D) {
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
return;
}
@ -405,11 +406,11 @@ void AP_Camera::log_picture()
if (!using_feedback_pin()) {
gcs().send_message(MSG_CAMERA_FEEDBACK);
if (df->should_log(log_camera_bit)) {
df->Log_Write_Camera(ahrs, gps, current_loc);
df->Log_Write_Camera(ahrs, current_loc);
}
} else {
if (df->should_log(log_camera_bit)) {
df->Log_Write_Trigger(ahrs, gps, current_loc);
df->Log_Write_Trigger(ahrs, current_loc);
}
}
}
@ -444,7 +445,7 @@ void AP_Camera::update_trigger()
DataFlash_Class *df = DataFlash_Class::instance();
if (df != nullptr) {
if (df->should_log(log_camera_bit)) {
df->Log_Write_Camera(ahrs, gps, current_loc);
df->Log_Write_Camera(ahrs, current_loc);
}
}
}

View File

@ -34,9 +34,8 @@ public:
static AP_Camera create(AP_Relay *obj_relay,
uint32_t _log_camera_bit,
const struct Location &_loc,
const AP_GPS &_gps,
const AP_AHRS &_ahrs) {
return AP_Camera{obj_relay, _log_camera_bit, _loc, _gps, _ahrs};
return AP_Camera{obj_relay, _log_camera_bit, _loc, _ahrs};
}
constexpr AP_Camera(AP_Camera &&other) = default;
@ -72,12 +71,11 @@ public:
void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; }
private:
AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_GPS &_gps, const AP_AHRS &_ahrs)
AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_AHRS &_ahrs)
: _trigger_counter(0) // count of number of cycles shutter has been held open
, _image_index(0)
, log_camera_bit(_log_camera_bit)
, current_loc(_loc)
, gps(_gps)
, ahrs(_ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
@ -123,7 +121,6 @@ private:
uint32_t log_camera_bit;
const struct Location &current_loc;
const AP_GPS &gps;
const AP_AHRS &ahrs;
// entry point to trip local shutter (e.g. by relay or servo)