Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Stop passing AHRS and relay objects to Camera object #11672

Merged
merged 6 commits into from Jul 8, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion APMrover2/Rover.h
Expand Up @@ -237,7 +237,7 @@ class Rover : public AP_HAL::HAL::Callbacks {

// Camera
#if CAMERA == ENABLED
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
AP_Camera camera{MASK_LOG_CAMERA, current_loc};
#endif

// Camera/Antenna mount tracking and stabilisation stuff
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.h
Expand Up @@ -486,7 +486,7 @@ class Copter : public AP_HAL::HAL::Callbacks {

// Camera
#if CAMERA == ENABLED
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
AP_Camera camera{MASK_LOG_CAMERA, current_loc};
#endif

// Camera/Antenna mount tracking and stabilisation stuff
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Expand Up @@ -291,7 +291,7 @@ class Plane : public AP_HAL::HAL::Callbacks {

// Camera
#if CAMERA == ENABLED
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
AP_Camera camera{MASK_LOG_CAMERA, current_loc};
#endif

#if OPTFLOW == ENABLED
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Sub.h
Expand Up @@ -406,7 +406,7 @@ class Sub : public AP_HAL::HAL::Callbacks {

// Camera
#if CAMERA == ENABLED
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
AP_Camera camera{MASK_LOG_CAMERA, current_loc};
#endif

// Camera/Antenna mount tracking and stabilisation stuff
Expand Down
23 changes: 18 additions & 5 deletions libraries/AP_Camera/AP_Camera.cpp
@@ -1,4 +1,6 @@
#include "AP_Camera.h"

#include <AP_AHRS/AP_AHRS.h>
#include <AP_Relay/AP_Relay.h>
#include <AP_Math/AP_Math.h>
#include <RC_Channel/RC_Channel.h>
Expand Down Expand Up @@ -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 {
Expand Down Expand Up @@ -164,14 +170,19 @@ 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 {
_apm_relay->on(0);
}
break;
}
}
}

if (_trigger_counter_cam_function) {
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
}

Expand Down Expand Up @@ -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);
}
}
}
Expand Down Expand Up @@ -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);
}
}
}
Expand Down
8 changes: 2 additions & 6 deletions libraries/AP_Camera/AP_Camera.h
Expand Up @@ -5,7 +5,7 @@
#include <AP_Param/AP_Param.h>
#include <AP_Common/AP_Common.h>
#include <AP_Relay/AP_Relay.h>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can't this be removed now?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

peter has said he'll do this separately

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

#define AP_CAMERA_TRIGGER_TYPE_SERVO 0
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1
Expand All @@ -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;
}

Expand Down Expand Up @@ -91,7 +89,6 @@ class AP_Camera {
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
Expand Down Expand Up @@ -124,7 +121,6 @@ class AP_Camera {

uint32_t log_camera_bit;
const struct Location &current_loc;
const AP_AHRS &ahrs;

// entry point to trip local shutter (e.g. by relay or servo)
void trigger_pic();
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Logger/AP_Logger.h
Expand Up @@ -246,9 +246,9 @@ class AP_Logger
void Write_Radio(const mavlink_radio_t &packet);
void Write_Message(const char *message);
void Write_MessageF(const char *fmt, ...);
void Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc, uint64_t timestamp_us=0);
void Write_Camera(const AP_AHRS &ahrs, const Location &current_loc, uint64_t timestamp_us=0);
void Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc);
void Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us=0);
void Write_Camera(const Location &current_loc, uint64_t timestamp_us=0);
void Write_Trigger(const Location &current_loc);
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot);
void Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
Expand Down
12 changes: 7 additions & 5 deletions libraries/AP_Logger/LogFile.cpp
Expand Up @@ -543,8 +543,10 @@ void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
}

// Write a Camera packet
void AP_Logger::Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc, uint64_t timestamp_us)
void AP_Logger::Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us)
{
const AP_AHRS &ahrs = AP::ahrs();

int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
Expand Down Expand Up @@ -578,15 +580,15 @@ void AP_Logger::Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, cons
}

// Write a Camera packet
void AP_Logger::Write_Camera(const AP_AHRS &ahrs, const Location &current_loc, uint64_t timestamp_us)
void AP_Logger::Write_Camera(const Location &current_loc, uint64_t timestamp_us)
{
Write_CameraInfo(LOG_CAMERA_MSG, ahrs, current_loc, timestamp_us);
Write_CameraInfo(LOG_CAMERA_MSG, current_loc, timestamp_us);
}

// Write a Trigger packet
void AP_Logger::Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc)
void AP_Logger::Write_Trigger(const Location &current_loc)
{
Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc, 0);
Write_CameraInfo(LOG_TRIGGER_MSG, current_loc, 0);
}

// Write an attitude packet
Expand Down