Browse Source

DataFlash: remove DataFlash.Log_Write_Message_P()

master
Lucas De Marchi 10 years ago committed by Randy Mackay
parent
commit
b52d1cfabb
  1. 1
      libraries/DataFlash/DataFlash.h
  2. 12
      libraries/DataFlash/LogFile.cpp

1
libraries/DataFlash/DataFlash.h

@ -107,7 +107,6 @@ public: @@ -107,7 +107,6 @@ public:
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
void Log_Write_Radio(const mavlink_radio_t &packet);
bool Log_Write_Message(const char *message);
bool Log_Write_Message_P(const prog_char_t *message);
void Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location &current_loc);
void Log_Write_ESC(void);
void Log_Write_Airspeed(AP_Airspeed &airspeed);

12
libraries/DataFlash/LogFile.cpp

@ -1060,18 +1060,6 @@ bool DataFlash_Class::Log_Write_Message(const char *message) @@ -1060,18 +1060,6 @@ bool DataFlash_Class::Log_Write_Message(const char *message)
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
// Write a text message to the log
bool DataFlash_Class::Log_Write_Message_P(const prog_char_t *message)
{
struct log_Message pkt = {
LOG_PACKET_HEADER_INIT(LOG_MESSAGE_MSG),
time_us : hal.scheduler->micros64(),
msg : {}
};
strncpy(pkt.msg, message, sizeof(pkt.msg));
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
// Write a POWR packet
void DataFlash_Class::Log_Write_Power(void)
{

Loading…
Cancel
Save