DataFlash: Log integer version of mission

This is higher precision the casting to float, and better matches the
internal format we actually use. Removed the indicection as it gained us
nothing. Closes #8875
This commit is contained in:
Michael du Breuil 2018-11-24 20:10:07 -07:00 committed by Tom Pittenger
parent 3296b1c7f7
commit 3ee675ad42
4 changed files with 21 additions and 30 deletions

View File

@ -121,7 +121,6 @@ public:
#if AP_AHRS_NAVEKF_AVAILABLE
void Log_Write_EKF(AP_AHRS_NavEKF &ahrs);
#endif
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
void Log_Write_Radio(const mavlink_radio_t &packet);
void Log_Write_Message(const char *message);
void Log_Write_MessageF(const char *fmt, ...);

View File

@ -89,7 +89,6 @@ public:
void Log_Write_EntireMission(const AP_Mission &mission);
bool Log_Write_Format(const struct LogStructure *structure);
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
bool Log_Write_Message(const char *message);
bool Log_Write_MessageF(const char *fmt, ...);
bool Log_Write_Mission_Cmd(const AP_Mission &mission,

View File

@ -409,13 +409,27 @@ void DataFlash_Class::Log_Write_Vibration()
WriteBlock(&pkt, sizeof(pkt));
}
// Write a mission command. Total length : 36 bytes
bool DataFlash_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission,
const AP_Mission::Mission_Command &cmd)
{
mavlink_mission_item_t mav_cmd = {};
AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd);
return Log_Write_MavCmd(mission.num_commands(),mav_cmd);
mavlink_mission_item_int_t mav_cmd = {};
AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
time_us : AP_HAL::micros64(),
command_total : mission.num_commands(),
sequence : mav_cmd.seq,
command : mav_cmd.command,
param1 : mav_cmd.param1,
param2 : mav_cmd.param2,
param3 : mav_cmd.param3,
param4 : mav_cmd.param4,
latitude : mav_cmd.x,
longitude : mav_cmd.y,
altitude : mav_cmd.z,
frame : mav_cmd.frame
};
return WriteBlock(&pkt, sizeof(pkt));
}
void DataFlash_Backend::Log_Write_EntireMission(const AP_Mission &mission)
@ -1276,27 +1290,6 @@ void DataFlash_Class::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs)
}
#endif
// Write a command processing packet
bool DataFlash_Backend::Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd)
{
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
time_us : AP_HAL::micros64(),
command_total : (uint16_t)cmd_total,
sequence : (uint16_t)mav_cmd.seq,
command : (uint16_t)mav_cmd.command,
param1 : (float)mav_cmd.param1,
param2 : (float)mav_cmd.param2,
param3 : (float)mav_cmd.param3,
param4 : (float)mav_cmd.param4,
latitude : (float)mav_cmd.x,
longitude : (float)mav_cmd.y,
altitude : (float)mav_cmd.z,
frame : (uint8_t)mav_cmd.frame
};
return WriteBlock(&pkt, sizeof(pkt));
}
void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet)
{
struct log_Radio pkt = {

View File

@ -625,8 +625,8 @@ struct PACKED log_Cmd {
float param2;
float param3;
float param4;
float latitude;
float longitude;
int32_t latitude;
int32_t longitude;
float altitude;
uint8_t frame;
};
@ -1225,7 +1225,7 @@ Format characters in the format string for binary log messages
{ LOG_POWR_MSG, sizeof(log_POWR), \
"POWR","QffHB","TimeUS,Vcc,VServo,Flags,Safety", "svv--", "F00--" }, \
{ LOG_CMD_MSG, sizeof(log_Cmd), \
"CMD", "QHHHfffffffB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
{ LOG_RADIO_MSG, sizeof(log_Radio), \
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------" }, \
{ LOG_CAMERA_MSG, sizeof(log_Camera), \