mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Logger: Support new ModeReason
This commit is contained in:
parent
cb1b236439
commit
c369139be0
@ -705,7 +705,7 @@ void AP_Logger::Write_Message(const char *message)
|
||||
FOR_EACH_BACKEND(Write_Message(message));
|
||||
}
|
||||
|
||||
void AP_Logger::Write_Mode(uint8_t mode, uint8_t reason)
|
||||
void AP_Logger::Write_Mode(uint8_t mode, const ModeReason reason)
|
||||
{
|
||||
FOR_EACH_BACKEND(Write_Mode(mode, reason));
|
||||
}
|
||||
|
@ -18,6 +18,7 @@
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
#include <AP_Proximity/AP_Proximity.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor_Backend.h>
|
||||
#include <AP_Vehicle/ModeReason.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
@ -258,7 +259,7 @@ public:
|
||||
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Write_Current();
|
||||
void Write_Compass(uint64_t time_us=0);
|
||||
void Write_Mode(uint8_t mode, uint8_t reason);
|
||||
void Write_Mode(uint8_t mode, const ModeReason reason);
|
||||
|
||||
void Write_EntireMission();
|
||||
void Write_Command(const mavlink_command_int_t &packet, MAV_RESULT result, bool was_command_long=false);
|
||||
|
@ -93,7 +93,7 @@ public:
|
||||
bool Write_MessageF(const char *fmt, ...);
|
||||
bool Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
bool Write_Mode(uint8_t mode, uint8_t reason = 0);
|
||||
bool Write_Mode(uint8_t mode, const ModeReason reason = ModeReason::UNKNOWN);
|
||||
bool Write_Parameter(const char *name, float value);
|
||||
bool Write_Parameter(const AP_Param *ap,
|
||||
const AP_Param::ParamToken &token,
|
||||
|
@ -760,14 +760,15 @@ void AP_Logger::Write_Compass(uint64_t time_us)
|
||||
}
|
||||
|
||||
// Write a mode packet.
|
||||
bool AP_Logger_Backend::Write_Mode(uint8_t mode, uint8_t reason)
|
||||
bool AP_Logger_Backend::Write_Mode(uint8_t mode, const ModeReason reason)
|
||||
{
|
||||
static_assert(sizeof(ModeReason) <= sizeof(uint8_t), "Logging expects the ModeReason to fit in 8 bits");
|
||||
const struct log_Mode pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
mode : mode,
|
||||
mode_num : mode,
|
||||
mode_reason : reason
|
||||
mode_reason : static_cast<uint8_t>(reason)
|
||||
};
|
||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user