Browse Source

Copter: move handling Write_Event into AP_Logger

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
3521d98b52
  1. 2
      ArduCopter/Copter.h
  2. 21
      ArduCopter/Log.cpp
  3. 61
      ArduCopter/defines.h
  4. 4
      ArduCopter/mode.cpp
  5. 2
      ArduCopter/mode.h
  6. 2
      ArduCopter/mode_autotune.cpp
  7. 1
      ArduSub/defines.h

2
ArduCopter/Copter.h

@ -757,7 +757,7 @@ private: @@ -757,7 +757,7 @@ private:
void Log_Write_Attitude();
void Log_Write_EKF_POS();
void Log_Write_MotBatt();
void Log_Write_Event(uint8_t id);
void Log_Write_Event(Log_Event id);
void Log_Write_Data(uint8_t id, int32_t value);
void Log_Write_Data(uint8_t id, uint32_t value);
void Log_Write_Data(uint8_t id, int16_t value);

21
ArduCopter/Log.cpp

@ -115,23 +115,10 @@ void Copter::Log_Write_MotBatt() @@ -115,23 +115,10 @@ void Copter::Log_Write_MotBatt()
#endif
}
struct PACKED log_Event {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
};
// Wrote an event packet
void Copter::Log_Write_Event(uint8_t id)
void Copter::Log_Write_Event(Log_Event id)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Event pkt = {
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
time_us : AP_HAL::micros64(),
id : id
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
logger.Write_Event(id);
}
struct PACKED log_Data_Int16t {
@ -424,8 +411,6 @@ const struct LogStructure Copter::log_structure[] = { @@ -424,8 +411,6 @@ const struct LogStructure Copter::log_structure[] = {
"CTUN", "Qffffffefcfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B0BBBB" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
{ LOG_EVENT_MSG, sizeof(log_Event),
"EV", "QB", "TimeUS,Id", "s-", "F-" },
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
@ -475,7 +460,7 @@ void Copter::Log_Write_Performance() {} @@ -475,7 +460,7 @@ void Copter::Log_Write_Performance() {}
void Copter::Log_Write_Attitude(void) {}
void Copter::Log_Write_EKF_POS() {}
void Copter::Log_Write_MotBatt() {}
void Copter::Log_Write_Event(uint8_t id) {}
void Copter::Log_Write_Event(Log_Event id) {}
void Copter::Log_Write_Data(uint8_t id, int32_t value) {}
void Copter::Log_Write_Data(uint8_t id, uint32_t value) {}
void Copter::Log_Write_Data(uint8_t id, int16_t value) {}

61
ArduCopter/defines.h

@ -240,7 +240,6 @@ enum LoggingParameters { @@ -240,7 +240,6 @@ enum LoggingParameters {
TYPE_AIRSTART_MSG,
TYPE_GROUNDSTART_MSG,
LOG_CONTROL_TUNING_MSG,
LOG_EVENT_MSG,
LOG_ERROR_MSG,
LOG_DATA_INT16_MSG,
LOG_DATA_UINT16_MSG,
@ -275,66 +274,6 @@ enum LoggingParameters { @@ -275,66 +274,6 @@ enum LoggingParameters {
#define MASK_LOG_IMU_RAW (1UL<<19)
#define MASK_LOG_ANY 0xFFFF
// DATA - event logging
#define DATA_AP_STATE 7
// 8 was DATA_SYSTEM_TIME_SET
#define DATA_INIT_SIMPLE_BEARING 9
#define DATA_ARMED 10
#define DATA_DISARMED 11
#define DATA_AUTO_ARMED 15
#define DATA_LAND_COMPLETE_MAYBE 17
#define DATA_LAND_COMPLETE 18
#define DATA_NOT_LANDED 28
#define DATA_LOST_GPS 19
#define DATA_FLIP_START 21
#define DATA_FLIP_END 22
#define DATA_SET_HOME 25
#define DATA_SET_SIMPLE_ON 26
#define DATA_SET_SIMPLE_OFF 27
#define DATA_SET_SUPERSIMPLE_ON 29
#define DATA_AUTOTUNE_INITIALISED 30
#define DATA_AUTOTUNE_OFF 31
#define DATA_AUTOTUNE_RESTART 32
#define DATA_AUTOTUNE_SUCCESS 33
#define DATA_AUTOTUNE_FAILED 34
#define DATA_AUTOTUNE_REACHED_LIMIT 35
#define DATA_AUTOTUNE_PILOT_TESTING 36
#define DATA_AUTOTUNE_SAVEDGAINS 37
#define DATA_SAVE_TRIM 38
#define DATA_SAVEWP_ADD_WP 39
#define DATA_FENCE_ENABLE 41
#define DATA_FENCE_DISABLE 42
#define DATA_ACRO_TRAINER_DISABLED 43
#define DATA_ACRO_TRAINER_LEVELING 44
#define DATA_ACRO_TRAINER_LIMITED 45
#define DATA_GRIPPER_GRAB 46
#define DATA_GRIPPER_RELEASE 47
#define DATA_PARACHUTE_DISABLED 49
#define DATA_PARACHUTE_ENABLED 50
#define DATA_PARACHUTE_RELEASED 51
#define DATA_LANDING_GEAR_DEPLOYED 52
#define DATA_LANDING_GEAR_RETRACTED 53
#define DATA_MOTORS_EMERGENCY_STOPPED 54
#define DATA_MOTORS_EMERGENCY_STOP_CLEARED 55
#define DATA_MOTORS_INTERLOCK_DISABLED 56
#define DATA_MOTORS_INTERLOCK_ENABLED 57
#define DATA_ROTOR_RUNUP_COMPLETE 58 // Heli only
#define DATA_ROTOR_SPEED_BELOW_CRITICAL 59 // Heli only
#define DATA_EKF_ALT_RESET 60
#define DATA_LAND_CANCELLED_BY_PILOT 61
#define DATA_EKF_YAW_RESET 62
#define DATA_AVOIDANCE_ADSB_ENABLE 63
#define DATA_AVOIDANCE_ADSB_DISABLE 64
#define DATA_AVOIDANCE_PROXIMITY_ENABLE 65
#define DATA_AVOIDANCE_PROXIMITY_DISABLE 66
#define DATA_GPS_PRIMARY_CHANGED 67
#define DATA_WINCH_RELAXED 68
#define DATA_WINCH_LENGTH_CONTROL 69
#define DATA_WINCH_RATE_CONTROL 70
#define DATA_ZIGZAG_STORE_A 71
#define DATA_ZIGZAG_STORE_B 72
#define DATA_LAND_REPO_ACTIVE 73
// Error message sub systems and error codes
#define ERROR_SUBSYSTEM_MAIN 1
#define ERROR_SUBSYSTEM_RADIO 2

4
ArduCopter/mode.cpp

@ -593,9 +593,9 @@ GCS_Copter &Copter::Mode::gcs() @@ -593,9 +593,9 @@ GCS_Copter &Copter::Mode::gcs()
return copter.gcs();
}
void Copter::Mode::Log_Write_Event(uint8_t id)
void Copter::Mode::Log_Write_Event(Log_Event id)
{
return copter.Log_Write_Event(id);
return copter.logger.Write_Event(id);
}
void Copter::Mode::set_throttle_takeoff()

2
ArduCopter/mode.h

@ -189,7 +189,7 @@ protected: @@ -189,7 +189,7 @@ protected:
bool set_mode(control_mode_t mode, mode_reason_t reason);
void set_land_complete(bool b);
GCS_Copter &gcs();
void Log_Write_Event(uint8_t id);
void Log_Write_Event(Log_Event id);
void set_throttle_takeoff(void);
float get_avoidance_adjusted_climbrate(float target_rate);
uint16_t get_pilot_speed_dn(void);

2
ArduCopter/mode_autotune.cpp

@ -128,7 +128,7 @@ void Copter::AutoTune::Log_Write_Event(enum at_event id) @@ -128,7 +128,7 @@ void Copter::AutoTune::Log_Write_Event(enum at_event id)
{
const struct {
enum at_event eid;
uint8_t id;
Log_Event id;
} map[] = {
{ EVENT_AUTOTUNE_INITIALISED, DATA_AUTOTUNE_INITIALISED },
{ EVENT_AUTOTUNE_OFF, DATA_AUTOTUNE_OFF },

1
ArduSub/defines.h

@ -105,7 +105,6 @@ enum LoggingParameters { @@ -105,7 +105,6 @@ enum LoggingParameters {
TYPE_AIRSTART_MSG,
TYPE_GROUNDSTART_MSG,
LOG_CONTROL_TUNING_MSG,
LOG_EVENT_MSG,
LOG_ERROR_MSG,
LOG_DATA_INT16_MSG,
LOG_DATA_UINT16_MSG,

Loading…
Cancel
Save