Copter: use common mission logging code
This commit is contained in:
parent
cabea266e7
commit
12bce49cd1
@ -588,7 +588,6 @@ private:
|
||||
void Log_Write_Rate();
|
||||
void Log_Write_MotBatt();
|
||||
void Log_Write_Startup();
|
||||
void Log_Write_EntireMission();
|
||||
void Log_Write_Event(uint8_t id);
|
||||
void Log_Write_Data(uint8_t id, int32_t value);
|
||||
void Log_Write_Data(uint8_t id, uint32_t value);
|
||||
@ -891,7 +890,6 @@ private:
|
||||
void print_hit_enter();
|
||||
void tuning();
|
||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
||||
void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd);
|
||||
bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||
|
||||
|
@ -1016,11 +1016,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS has sent us a command from GCS, store to EEPROM
|
||||
// GCS has sent us a mission item, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
|
||||
{
|
||||
if (handle_mission_item(msg, copter.mission)) {
|
||||
copter.Log_Write_EntireMission();
|
||||
copter.DataFlash.Log_Write_EntireMission(copter.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -353,14 +353,6 @@ void Copter::Log_Write_Performance()
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
// Write a mission command. Total length : 36 bytes
|
||||
void Copter::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
mavlink_mission_item_t mav_cmd = {};
|
||||
AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd);
|
||||
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
|
||||
}
|
||||
|
||||
// Write an attitude packet
|
||||
void Copter::Log_Write_Attitude()
|
||||
{
|
||||
@ -459,19 +451,7 @@ void Copter::Log_Write_Startup()
|
||||
|
||||
// write all commands to the dataflash as well
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_EntireMission();
|
||||
}
|
||||
}
|
||||
|
||||
void Copter::Log_Write_EntireMission()
|
||||
{
|
||||
DataFlash.Log_Write_Message_P(PSTR("New mission"));
|
||||
|
||||
AP_Mission::Mission_Command cmd;
|
||||
for (uint16_t i = 0; i < mission.num_commands(); i++) {
|
||||
if (mission.read_cmd_from_storage(i,cmd)) {
|
||||
Log_Write_Cmd(cmd);
|
||||
}
|
||||
DataFlash.Log_Write_EntireMission(mission);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -96,7 +96,7 @@ bool Copter::set_home(const Location& loc)
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
AP_Mission::Mission_Command temp_cmd;
|
||||
if (mission.read_cmd_from_storage(0, temp_cmd)) {
|
||||
Log_Write_Cmd(temp_cmd);
|
||||
DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -7,7 +7,7 @@ bool Copter::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// To-Do: logging when new commands start/end
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_Cmd(cmd);
|
||||
DataFlash.Log_Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
|
||||
switch(cmd.id) {
|
||||
|
Loading…
Reference in New Issue
Block a user