Browse Source

Copter: rename MOT df msg to MOTB

This will slightly reduce confusion with the MOT message from AC3.1.5
that eventually became RCOUT
master
Randy Mackay 10 years ago
parent
commit
522ef8f91f
  1. 4
      ArduCopter/ArduCopter.pde
  2. 30
      ArduCopter/Log.pde
  3. 2
      ArduCopter/config.h
  4. 4
      ArduCopter/defines.h

4
ArduCopter/ArduCopter.pde

@ -1040,8 +1040,8 @@ static void ten_hz_logging_loop() @@ -1040,8 +1040,8 @@ static void ten_hz_logging_loop()
Log_Write_Attitude();
Log_Write_Rate();
}
if (should_log(MASK_LOG_MOT)) {
Log_Write_Mot();
if (should_log(MASK_LOG_MOTBATT)) {
Log_Write_MotBatt();
}
if (should_log(MASK_LOG_RCIN)) {
DataFlash.Log_Write_RCIN();

30
ArduCopter/Log.pde

@ -364,15 +364,6 @@ static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) @@ -364,15 +364,6 @@ static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
}
struct PACKED log_Mot {
LOG_PACKET_HEADER;
uint32_t time_ms;
float lift_max;
float bat_volt;
float bat_res;
float th_limit;
};
// Write an attitude packet
static void Log_Write_Attitude()
{
@ -426,11 +417,20 @@ static void Log_Write_Rate() @@ -426,11 +417,20 @@ static void Log_Write_Rate()
DataFlash.WriteBlock(&pkt_rate, sizeof(pkt_rate));
}
struct PACKED log_MotBatt {
LOG_PACKET_HEADER;
uint32_t time_ms;
float lift_max;
float bat_volt;
float bat_res;
float th_limit;
};
// Write an rate packet
static void Log_Write_Mot()
static void Log_Write_MotBatt()
{
struct log_Mot pkt_mot = {
LOG_PACKET_HEADER_INIT(LOG_MOT_MSG),
struct log_MotBatt pkt_mot = {
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
time_ms : hal.scheduler->millis(),
lift_max : (float)(motors.get_lift_max()),
bat_volt : (float)(motors.get_batt_voltage_filt()),
@ -608,8 +608,8 @@ static const struct LogStructure log_structure[] PROGMEM = { @@ -608,8 +608,8 @@ static const struct LogStructure log_structure[] PROGMEM = {
"PM", "HHIhBH", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
{ LOG_RATE_MSG, sizeof(log_Rate),
"RATE", "Ifffffffff", "TimeMS,RllDes,Rll,RllOut,PitDes,Pit,PitOut,YawDes,Yaw,YawOut" },
{ LOG_MOT_MSG, sizeof(log_Mot),
"MOT", "Iffff", "TimeMS,LiftMax,BatVolt,BatRes,ThLimit" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Iffff", "TimeMS,LiftMax,BatVolt,BatRes,ThLimit" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "", "" },
{ LOG_EVENT_MSG, sizeof(log_Event),
@ -685,7 +685,7 @@ static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {} @@ -685,7 +685,7 @@ static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
static void Log_Write_Current() {}
static void Log_Write_Attitude() {}
static void Log_Write_Rate() {}
static void Log_Write_Mot() {}
static void Log_Write_MotBatt() {}
static void Log_Write_Data(uint8_t id, int16_t value){}
static void Log_Write_Data(uint8_t id, uint16_t value){}
static void Log_Write_Data(uint8_t id, int32_t value){}

2
ArduCopter/config.h

@ -686,7 +686,7 @@ @@ -686,7 +686,7 @@
MASK_LOG_OPTFLOW | \
MASK_LOG_COMPASS | \
MASK_LOG_CAMERA | \
MASK_LOG_MOT
MASK_LOG_MOTBATT
#endif
//////////////////////////////////////////////////////////////////////////////

4
ArduCopter/defines.h

@ -240,7 +240,7 @@ enum FlipState { @@ -240,7 +240,7 @@ enum FlipState {
#define LOG_AUTOTUNE_MSG 0x19
#define LOG_AUTOTUNEDETAILS_MSG 0x1A
#define LOG_RATE_MSG 0x1D
#define LOG_MOT_MSG 0x1E
#define LOG_MOTBATT_MSG 0x1E
#define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1)
@ -259,7 +259,7 @@ enum FlipState { @@ -259,7 +259,7 @@ enum FlipState {
#define MASK_LOG_INAV (1<<14) // deprecated
#define MASK_LOG_CAMERA (1<<15)
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
#define MASK_LOG_MOT (1UL<<17)
#define MASK_LOG_MOTBATT (1UL<<17)
#define MASK_LOG_ANY 0xFFFF
// DATA - event logging

Loading…
Cancel
Save