mirror of https://github.com/ArduPilot/ardupilot
Plane: use common Log_Write_Camera
pair programmed with Craig Elder
This commit is contained in:
parent
4d93dd47ee
commit
ac65119cfe
|
@ -235,37 +235,6 @@ static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
|
|||
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
|
||||
}
|
||||
|
||||
struct PACKED log_Camera {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t gps_time;
|
||||
uint16_t gps_week;
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t altitude;
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
uint16_t yaw;
|
||||
};
|
||||
|
||||
// Write a Camera packet. Total length : 26 bytes
|
||||
static void Log_Write_Camera()
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
struct log_Camera pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
|
||||
gps_time : gps.time_week_ms(),
|
||||
gps_week : gps.time_week(),
|
||||
latitude : current_loc.lat,
|
||||
longitude : current_loc.lng,
|
||||
altitude : current_loc.alt,
|
||||
roll : (int16_t)ahrs.roll_sensor,
|
||||
pitch : (int16_t)ahrs.pitch_sensor,
|
||||
yaw : (uint16_t)ahrs.yaw_sensor
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
#endif
|
||||
}
|
||||
|
||||
struct PACKED log_Startup {
|
||||
LOG_PACKET_HEADER;
|
||||
uint8_t startup_type;
|
||||
|
@ -543,8 +512,6 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
|||
"ATT", "IccCCC", "TimeMS,Roll,Pitch,Yaw,ErrorRP,ErrorYaw" },
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "IHIhhhBH", "LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
|
||||
{ LOG_CAMERA_MSG, sizeof(log_Camera),
|
||||
"CAM", "IHLLeccC", "GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "BH", "SType,CTot" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
|
@ -611,7 +578,6 @@ static void Log_Write_Performance() {}
|
|||
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {}
|
||||
static void Log_Write_Attitude() {}
|
||||
static void Log_Write_Control_Tuning() {}
|
||||
static void Log_Write_Camera() {}
|
||||
static void Log_Write_Mode(uint8_t mode) {}
|
||||
static void Log_Write_Compass() {}
|
||||
static void Log_Write_GPS(uint8_t instance) {}
|
||||
|
|
|
@ -596,7 +596,7 @@ static void do_take_picture()
|
|||
#if CAMERA == ENABLED
|
||||
camera.trigger_pic();
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
Log_Write_Camera();
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -117,7 +117,7 @@ enum log_messages {
|
|||
LOG_STARTUP_MSG,
|
||||
TYPE_AIRSTART_MSG,
|
||||
TYPE_GROUNDSTART_MSG,
|
||||
LOG_CAMERA_MSG,
|
||||
LOG_CAMERA_MSG_DEPRECATED,
|
||||
LOG_ATTITUDE_MSG,
|
||||
LOG_MODE_MSG,
|
||||
LOG_COMPASS_MSG,
|
||||
|
|
Loading…
Reference in New Issue