From 01773d90259191ba4e2cb89dc7183949ed5e9372 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 27 Jun 2019 17:23:37 +1000 Subject: [PATCH] AP_Camera: use singletons for relay and ahrs insead of storing references --- libraries/AP_Camera/AP_Camera.cpp | 23 ++++++++++++++++++----- libraries/AP_Camera/AP_Camera.h | 8 ++------ 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index bde46339f2..4d25e91eea 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -1,4 +1,6 @@ #include "AP_Camera.h" + +#include #include #include #include @@ -123,6 +125,10 @@ AP_Camera::servo_pic() void AP_Camera::relay_pic() { + AP_Relay *_apm_relay = AP::relay(); + if (_apm_relay == nullptr) { + return; + } if (_relay_on) { _apm_relay->on(0); } else { @@ -164,7 +170,11 @@ AP_Camera::trigger_pic_cleanup() case AP_CAMERA_TRIGGER_TYPE_SERVO: SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _servo_off_pwm); break; - case AP_CAMERA_TRIGGER_TYPE_RELAY: + case AP_CAMERA_TRIGGER_TYPE_RELAY: { + AP_Relay *_apm_relay = AP::relay(); + if (_apm_relay == nullptr) { + break; + } if (_relay_on) { _apm_relay->off(0); } else { @@ -172,6 +182,7 @@ AP_Camera::trigger_pic_cleanup() } break; } + } } if (_trigger_counter_cam_function) { @@ -274,6 +285,8 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo */ void AP_Camera::send_feedback(mavlink_channel_t chan) { + const AP_AHRS &ahrs = AP::ahrs(); + float altitude, altitude_rel; if (current_loc.relative_alt) { altitude = current_loc.alt+ahrs.get_home().alt; @@ -319,7 +332,7 @@ void AP_Camera::update() return; } - if (_max_roll > 0 && fabsf(ahrs.roll_sensor*1e-2f) > _max_roll) { + if (_max_roll > 0 && fabsf(AP::ahrs().roll_sensor*1e-2f) > _max_roll) { return; } @@ -402,11 +415,11 @@ void AP_Camera::log_picture() if (!using_feedback_pin()) { gcs().send_message(MSG_CAMERA_FEEDBACK); if (logger->should_log(log_camera_bit)) { - logger->Write_Camera(ahrs, current_loc); + logger->Write_Camera(current_loc); } } else { if (logger->should_log(log_camera_bit)) { - logger->Write_Trigger(ahrs, current_loc); + logger->Write_Trigger(current_loc); } } } @@ -447,7 +460,7 @@ void AP_Camera::update_trigger() if (logger->should_log(log_camera_bit)) { uint32_t tdiff = AP_HAL::micros() - timestamp32; uint64_t timestamp = AP_HAL::micros64(); - logger->Write_Camera(ahrs, current_loc, timestamp - tdiff); + logger->Write_Camera(current_loc, timestamp - tdiff); } } } diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index a52ff1e65e..c25c2e0561 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -5,7 +5,7 @@ #include #include #include -#include +#include #define AP_CAMERA_TRIGGER_TYPE_SERVO 0 #define AP_CAMERA_TRIGGER_TYPE_RELAY 1 @@ -24,13 +24,11 @@ class AP_Camera { public: - AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_AHRS &_ahrs) + AP_Camera(uint32_t _log_camera_bit, const struct Location &_loc) : log_camera_bit(_log_camera_bit) , current_loc(_loc) - , ahrs(_ahrs) { AP_Param::setup_object_defaults(this, var_info); - _apm_relay = obj_relay; _singleton = this; } @@ -91,7 +89,6 @@ private: AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated uint8_t _trigger_counter; // count of number of cycles shutter has been held open uint8_t _trigger_counter_cam_function; // count of number of cycles alternative camera function has been held open - AP_Relay *_apm_relay; // pointer to relay object from the base class Relay. AP_Int8 _auto_mode_only; // if 1: trigger by distance only if in AUTO mode. AP_Int8 _type; // Set the type of camera in use, will open additional parameters if set bool _is_in_auto_mode; // true if in AUTO mode @@ -124,7 +121,6 @@ private: uint32_t log_camera_bit; const struct Location ¤t_loc; - const AP_AHRS &ahrs; // entry point to trip local shutter (e.g. by relay or servo) void trigger_pic();