mirror of https://github.com/ArduPilot/ardupilot
Sub: cope with change in namespace of LogEvent enum
Also eliminate the Log_Write_Event wrappers
This commit is contained in:
parent
e6c6189fe5
commit
3819366a9e
|
@ -121,7 +121,7 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
|
|||
|
||||
// Always use absolute altitude for ROV
|
||||
// ahrs.resetHeightDatum();
|
||||
// Log_Write_Event(DATA_EKF_ALT_RESET);
|
||||
// AP::logger().Write_Event(LogEvent::EKF_ALT_RESET);
|
||||
} else if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
||||
// Reset home position if it has already been set before (but not locked)
|
||||
if (!sub.set_home_to_current_location(false)) {
|
||||
|
@ -139,7 +139,7 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
|
|||
// finally actually arm the motors
|
||||
sub.motors.armed(true);
|
||||
|
||||
AP::logger().Write_Event(DATA_ARMED);
|
||||
AP::logger().Write_Event(LogEvent::ARMED);
|
||||
|
||||
// log flight mode in case it was changed while vehicle was disarmed
|
||||
AP::logger().Write_Mode(sub.control_mode, sub.control_mode_reason);
|
||||
|
@ -184,7 +184,7 @@ bool AP_Arming_Sub::disarm()
|
|||
}
|
||||
}
|
||||
|
||||
AP::logger().Write_Event(DATA_DISARMED);
|
||||
AP::logger().Write_Event(LogEvent::DISARMED);
|
||||
|
||||
// send disarm command to motors
|
||||
sub.motors.armed(false);
|
||||
|
|
|
@ -268,7 +268,7 @@ void Sub::one_hz_loop()
|
|||
AP_Notify::flags.flying = motors.armed();
|
||||
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
Log_Write_Data(DATA_AP_STATE, ap.value);
|
||||
Log_Write_Data(LogDataID::AP_STATE, ap.value);
|
||||
}
|
||||
|
||||
if (!motors.armed()) {
|
||||
|
|
|
@ -88,12 +88,6 @@ void Sub::Log_Write_MotBatt()
|
|||
logger.WriteBlock(&pkt_mot, sizeof(pkt_mot));
|
||||
}
|
||||
|
||||
// Wrote an event packet
|
||||
void Sub::Log_Write_Event(Log_Event id)
|
||||
{
|
||||
logger.Write_Event(id);
|
||||
}
|
||||
|
||||
struct PACKED log_Data_Int16t {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
|
@ -103,13 +97,13 @@ struct PACKED log_Data_Int16t {
|
|||
|
||||
// Write an int16_t data packet
|
||||
UNUSED_FUNCTION
|
||||
void Sub::Log_Write_Data(uint8_t id, int16_t value)
|
||||
void Sub::Log_Write_Data(LogDataID id, int16_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Int16t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
|
@ -125,13 +119,13 @@ struct PACKED log_Data_UInt16t {
|
|||
|
||||
// Write an uint16_t data packet
|
||||
UNUSED_FUNCTION
|
||||
void Sub::Log_Write_Data(uint8_t id, uint16_t value)
|
||||
void Sub::Log_Write_Data(LogDataID id, uint16_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_UInt16t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
|
@ -146,13 +140,13 @@ struct PACKED log_Data_Int32t {
|
|||
};
|
||||
|
||||
// Write an int32_t data packet
|
||||
void Sub::Log_Write_Data(uint8_t id, int32_t value)
|
||||
void Sub::Log_Write_Data(LogDataID id, int32_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Int32t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
|
@ -167,13 +161,13 @@ struct PACKED log_Data_UInt32t {
|
|||
};
|
||||
|
||||
// Write a uint32_t data packet
|
||||
void Sub::Log_Write_Data(uint8_t id, uint32_t value)
|
||||
void Sub::Log_Write_Data(LogDataID id, uint32_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_UInt32t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
|
@ -189,13 +183,13 @@ struct PACKED log_Data_Float {
|
|||
|
||||
// Write a float data packet
|
||||
UNUSED_FUNCTION
|
||||
void Sub::Log_Write_Data(uint8_t id, float value)
|
||||
void Sub::Log_Write_Data(LogDataID id, float value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Float pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
|
@ -290,7 +284,6 @@ void Sub::Log_Write_Control_Tuning() {}
|
|||
void Sub::Log_Write_Performance() {}
|
||||
void Sub::Log_Write_Attitude(void) {}
|
||||
void Sub::Log_Write_MotBatt() {}
|
||||
void Sub::Log_Write_Event(Log_Event id) {}
|
||||
void Sub::Log_Write_Data(uint8_t id, int32_t value) {}
|
||||
void Sub::Log_Write_Data(uint8_t id, uint32_t value) {}
|
||||
void Sub::Log_Write_Data(uint8_t id, int16_t value) {}
|
||||
|
|
|
@ -454,12 +454,11 @@ private:
|
|||
void Log_Write_Performance();
|
||||
void Log_Write_Attitude();
|
||||
void Log_Write_MotBatt();
|
||||
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);
|
||||
void Log_Write_Data(uint8_t id, uint16_t value);
|
||||
void Log_Write_Data(uint8_t id, float value);
|
||||
void Log_Write_Data(LogDataID id, int32_t value);
|
||||
void Log_Write_Data(LogDataID id, uint32_t value);
|
||||
void Log_Write_Data(LogDataID id, int16_t value);
|
||||
void Log_Write_Data(LogDataID id, uint16_t value);
|
||||
void Log_Write_Data(LogDataID id, float value);
|
||||
void Log_Sensor_Health();
|
||||
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
|
|
|
@ -73,7 +73,7 @@ bool Sub::set_home(const Location& loc, bool lock)
|
|||
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
|
||||
scaleLongDown = loc.longitude_scale();
|
||||
// record home is set
|
||||
Log_Write_Event(DATA_SET_HOME);
|
||||
AP::logger().Write_Event(LogEvent::SET_HOME);
|
||||
|
||||
// log new home position which mission library will pull from ahrs
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
|
|
|
@ -90,9 +90,9 @@ void Sub::set_surfaced(bool at_surface)
|
|||
surface_detector_count = 0;
|
||||
|
||||
if (ap.at_surface) {
|
||||
Log_Write_Event(DATA_SURFACED);
|
||||
AP::logger().Write_Event(LogEvent::SURFACED);
|
||||
} else {
|
||||
Log_Write_Event(DATA_NOT_SURFACED);
|
||||
AP::logger().Write_Event(LogEvent::NOT_SURFACED);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -108,8 +108,8 @@ void Sub::set_bottomed(bool at_bottom)
|
|||
bottom_detector_count = 0;
|
||||
|
||||
if (ap.at_bottom) {
|
||||
Log_Write_Event(DATA_BOTTOMED);
|
||||
AP::logger().Write_Event(LogEvent::BOTTOMED);
|
||||
} else {
|
||||
Log_Write_Event(DATA_NOT_BOTTOMED);
|
||||
AP::logger().Write_Event(LogEvent::NOT_BOTTOMED);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue