mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: Enable default airspeed variance to be specified externally
This commit is contained in:
parent
9228925bea
commit
296fb567ca
|
@ -174,11 +174,12 @@ void AP_DAL::log_SetOriginLLH2(const Location &loc)
|
|||
#endif
|
||||
}
|
||||
|
||||
void AP_DAL::log_writeDefaultAirSpeed2(const float aspeed)
|
||||
void AP_DAL::log_writeDefaultAirSpeed2(const float aspeed, const float uncertainty)
|
||||
{
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
struct log_RWA2 pkt{
|
||||
airspeed: aspeed,
|
||||
uncertainty: uncertainty,
|
||||
};
|
||||
WRITE_REPLAY_BLOCK(RWA2, pkt);
|
||||
#endif
|
||||
|
@ -207,11 +208,12 @@ void AP_DAL::log_SetOriginLLH3(const Location &loc)
|
|||
#endif
|
||||
}
|
||||
|
||||
void AP_DAL::log_writeDefaultAirSpeed3(const float aspeed)
|
||||
void AP_DAL::log_writeDefaultAirSpeed3(const float aspeed, const float uncertainty)
|
||||
{
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
struct log_RWA3 pkt{
|
||||
airspeed: aspeed,
|
||||
uncertainty: uncertainty
|
||||
};
|
||||
WRITE_REPLAY_BLOCK(RWA3, pkt);
|
||||
#endif
|
||||
|
|
|
@ -75,11 +75,11 @@ public:
|
|||
|
||||
void log_event2(Event event);
|
||||
void log_SetOriginLLH2(const Location &loc);
|
||||
void log_writeDefaultAirSpeed2(float aspeed);
|
||||
void log_writeDefaultAirSpeed2(const float aspeed, const float uncertainty);
|
||||
|
||||
void log_event3(Event event);
|
||||
void log_SetOriginLLH3(const Location &loc);
|
||||
void log_writeDefaultAirSpeed3(float aspeed);
|
||||
void log_writeDefaultAirSpeed3(const float aspeed, const float uncertainty);
|
||||
void log_writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type);
|
||||
|
||||
enum class StateMask {
|
||||
|
|
|
@ -115,6 +115,7 @@ struct log_RSO2 {
|
|||
// @Description: Replay set-default-airspeed event
|
||||
struct log_RWA2 {
|
||||
float airspeed;
|
||||
float uncertainty;
|
||||
uint8_t _end;
|
||||
};
|
||||
|
||||
|
@ -365,13 +366,13 @@ struct log_RBOH {
|
|||
{ LOG_RSO2_MSG, RLOG_SIZE(RSO2), \
|
||||
"RSO2", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \
|
||||
{ LOG_RWA2_MSG, RLOG_SIZE(RWA2), \
|
||||
"RWA2", "f", "Airspeed", "n", "0" }, \
|
||||
"RWA2", "ff", "Airspeed,uncertainty", "nn", "00" }, \
|
||||
{ LOG_REV3_MSG, RLOG_SIZE(REV3), \
|
||||
"REV3", "B", "Event", "-", "-" }, \
|
||||
{ LOG_RSO3_MSG, RLOG_SIZE(RSO3), \
|
||||
"RSO3", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \
|
||||
{ LOG_RWA3_MSG, RLOG_SIZE(RWA3), \
|
||||
"RWA3", "f", "Airspeed", "n", "0" }, \
|
||||
"RWA3", "ff", "Airspeed,Uncertainty", "nn", "00" }, \
|
||||
{ LOG_REY3_MSG, RLOG_SIZE(REY3), \
|
||||
"REY3", "ffIB", "yawangle,yawangleerr,timestamp_ms,type", "???-", "???-" }, \
|
||||
{ LOG_RISH_MSG, RLOG_SIZE(RISH), \
|
||||
|
|
Loading…
Reference in New Issue