mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: use common mission logging code
This commit is contained in:
parent
12bce49cd1
commit
3fce7eb21a
@ -1460,11 +1460,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:
|
||||
{
|
||||
if (handle_mission_item(msg, plane.mission)) {
|
||||
plane.Log_Write_EntireMission();
|
||||
plane.DataFlash.Log_Write_EntireMission(plane.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -221,14 +221,6 @@ void Plane::Log_Write_Performance()
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
// Write a mission command. Total length : 36 bytes
|
||||
void Plane::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);
|
||||
}
|
||||
|
||||
struct PACKED log_Startup {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
@ -248,19 +240,7 @@ void Plane::Log_Write_Startup(uint8_t type)
|
||||
|
||||
// write all commands to the dataflash as well
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_EntireMission();
|
||||
}
|
||||
}
|
||||
|
||||
void Plane::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);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -672,7 +672,6 @@ private:
|
||||
void Log_Write_Attitude(void);
|
||||
void Log_Write_Performance();
|
||||
void Log_Write_Startup(uint8_t type);
|
||||
void Log_Write_EntireMission();
|
||||
void Log_Write_Control_Tuning();
|
||||
void Log_Write_TECS_Tuning(void);
|
||||
void Log_Write_Nav_Tuning();
|
||||
@ -906,7 +905,6 @@ private:
|
||||
void do_digicam_control(const AP_Mission::Mission_Command& cmd);
|
||||
bool start_command_callback(const AP_Mission::Mission_Command &cmd);
|
||||
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
||||
void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd);
|
||||
void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
||||
void run_cli(AP_HAL::UARTDriver *port);
|
||||
void log_init();
|
||||
|
@ -9,7 +9,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// log when new commands start
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_Cmd(cmd);
|
||||
DataFlash.Log_Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
|
||||
// special handling for nav vs non-nav commands
|
||||
|
Loading…
Reference in New Issue
Block a user