DataFlash: AP_Camera functions use GPS singleton
This commit is contained in:
parent
7258fa81d9
commit
b97ee33438
@ -135,9 +135,9 @@ public:
|
|||||||
void Log_Write_Radio(const mavlink_radio_t &packet);
|
void Log_Write_Radio(const mavlink_radio_t &packet);
|
||||||
void Log_Write_Message(const char *message);
|
void Log_Write_Message(const char *message);
|
||||||
void Log_Write_MessageF(const char *fmt, ...);
|
void Log_Write_MessageF(const char *fmt, ...);
|
||||||
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc);
|
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc);
|
||||||
void Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc);
|
void Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc);
|
||||||
void Log_Write_Trigger(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc);
|
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc);
|
||||||
void Log_Write_ESC(void);
|
void Log_Write_ESC(void);
|
||||||
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
||||||
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
||||||
|
@ -1409,7 +1409,7 @@ void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Write a Camera packet
|
// Write a Camera packet
|
||||||
void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc)
|
void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc)
|
||||||
{
|
{
|
||||||
int32_t altitude, altitude_rel, altitude_gps;
|
int32_t altitude, altitude_rel, altitude_gps;
|
||||||
if (current_loc.flags.relative_alt) {
|
if (current_loc.flags.relative_alt) {
|
||||||
@ -1419,6 +1419,7 @@ void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &
|
|||||||
altitude = current_loc.alt;
|
altitude = current_loc.alt;
|
||||||
altitude_rel = current_loc.alt - ahrs.get_home().alt;
|
altitude_rel = current_loc.alt - ahrs.get_home().alt;
|
||||||
}
|
}
|
||||||
|
const AP_GPS &gps = AP::gps();
|
||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
altitude_gps = gps.location().alt;
|
altitude_gps = gps.location().alt;
|
||||||
} else {
|
} else {
|
||||||
@ -1443,15 +1444,15 @@ void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Write a Camera packet
|
// Write a Camera packet
|
||||||
void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc)
|
void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc)
|
||||||
{
|
{
|
||||||
Log_Write_CameraInfo(LOG_CAMERA_MSG, ahrs, gps, current_loc);
|
Log_Write_CameraInfo(LOG_CAMERA_MSG, ahrs, current_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a Trigger packet
|
// Write a Trigger packet
|
||||||
void DataFlash_Class::Log_Write_Trigger(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc)
|
void DataFlash_Class::Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
|
||||||
{
|
{
|
||||||
Log_Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, gps, current_loc);
|
Log_Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write an attitude packet
|
// Write an attitude packet
|
||||||
|
Loading…
Reference in New Issue
Block a user