Browse Source

Copter: use Dataflash lib's Log_Write_Cmd

master
Randy Mackay 11 years ago
parent
commit
f3813593b7
  1. 32
      ArduCopter/Log.pde
  2. 2
      ArduCopter/commands.pde
  3. 2
      ArduCopter/commands_logic.pde
  4. 1
      ArduCopter/defines.h

32
ArduCopter/Log.pde

@ -422,35 +422,6 @@ static void Log_Write_Performance()
DataFlash.WriteBlock(&pkt, sizeof(pkt)); DataFlash.WriteBlock(&pkt, sizeof(pkt));
} }
struct PACKED log_Cmd {
LOG_PACKET_HEADER;
uint16_t command_total;
uint16_t command_number;
uint8_t waypoint_id;
uint8_t waypoint_options;
uint8_t waypoint_param1;
int32_t waypoint_altitude;
int32_t waypoint_latitude;
int32_t waypoint_longitude;
};
// Write a command processing packet
static void Log_Write_Cmd(const AP_Mission::Mission_Command& cmd)
{
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
command_total : mission.num_commands(),
command_number : cmd.index,
waypoint_id : cmd.id,
waypoint_options : cmd.content.location.options,
waypoint_param1 : cmd.p1,
waypoint_altitude : cmd.content.location.alt,
waypoint_latitude : cmd.content.location.lat,
waypoint_longitude : cmd.content.location.lng
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_Attitude { struct PACKED log_Attitude {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint32_t time_ms;
@ -705,8 +676,6 @@ static const struct LogStructure log_structure[] PROGMEM = {
"MAG2","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" }, "MAG2","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), { LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "HHIhBHB", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" }, "PM", "HHIhBHB", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
{ LOG_CMD_MSG, sizeof(log_Cmd),
"CMD", "HHBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude), { LOG_ATTITUDE_MSG, sizeof(log_Attitude),
"ATT", "IccccCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw" }, "ATT", "IccccCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw" },
{ LOG_MODE_MSG, sizeof(log_Mode), { LOG_MODE_MSG, sizeof(log_Mode),
@ -781,7 +750,6 @@ static void start_logging()
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
static void Log_Write_Startup() {} static void Log_Write_Startup() {}
static void Log_Write_Cmd(const AP_Mission::Mission_Command& cmd) {}
static void Log_Write_Mode(uint8_t mode) {} static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_IMU() {} static void Log_Write_IMU() {}
static void Log_Write_GPS() {} static void Log_Write_GPS() {}

2
ArduCopter/commands.pde

@ -24,7 +24,7 @@ static void init_home()
if (g.log_bitmask & MASK_LOG_CMD) { if (g.log_bitmask & MASK_LOG_CMD) {
AP_Mission::Mission_Command temp_cmd; AP_Mission::Mission_Command temp_cmd;
if (mission.read_cmd_from_storage(0, temp_cmd)) { if (mission.read_cmd_from_storage(0, temp_cmd)) {
Log_Write_Cmd(temp_cmd); DataFlash.Log_Write_Cmd(mission.num_commands(),temp_cmd);
} }
} }

2
ArduCopter/commands_logic.pde

@ -21,7 +21,7 @@ static bool start_command(const AP_Mission::Mission_Command& cmd)
{ {
// To-Do: logging when new commands start/end // To-Do: logging when new commands start/end
if (g.log_bitmask & MASK_LOG_CMD) { if (g.log_bitmask & MASK_LOG_CMD) {
Log_Write_Cmd(cmd); DataFlash.Log_Write_Cmd(mission.num_commands(),cmd);
} }
switch(cmd.id) { switch(cmd.id) {

1
ArduCopter/defines.h

@ -215,7 +215,6 @@ enum FlipState {
#define LOG_CONTROL_TUNING_MSG 0x04 #define LOG_CONTROL_TUNING_MSG 0x04
#define LOG_NAV_TUNING_MSG 0x05 #define LOG_NAV_TUNING_MSG 0x05
#define LOG_PERFORMANCE_MSG 0x06 #define LOG_PERFORMANCE_MSG 0x06
#define LOG_CMD_MSG 0x08
#define LOG_CURRENT_MSG 0x09 #define LOG_CURRENT_MSG 0x09
#define LOG_STARTUP_MSG 0x0A #define LOG_STARTUP_MSG 0x0A
#define LOG_OPTFLOW_MSG 0x0C #define LOG_OPTFLOW_MSG 0x0C

Loading…
Cancel
Save