AP_Logger: use singletons when logging camera information

This commit is contained in:
Peter Barker 2019-06-27 17:24:04 +10:00 committed by Andrew Tridgell
parent 01773d9025
commit 7c102b90fa
2 changed files with 10 additions and 8 deletions

View File

@ -246,9 +246,9 @@ public:
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);

View File

@ -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;
@ -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