mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_DAL: add wheelencoder_enabled
This commit is contained in:
parent
3984cdd823
commit
7d319f8059
@ -5,6 +5,7 @@
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
@ -65,6 +66,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
|
||||
_RFRN.available_memory = hal.util->available_memory();
|
||||
_RFRN.ahrs_trim = ahrs.get_trim();
|
||||
_RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled();
|
||||
_RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0);
|
||||
WRITE_REPLAY_BLOCK_IFCHANGED(RFRN, _RFRN, old);
|
||||
|
||||
// update body conversion
|
||||
|
@ -192,6 +192,10 @@ public:
|
||||
return _RFRN.opticalflow_enabled;
|
||||
}
|
||||
|
||||
bool wheelencoder_enabled(void) const {
|
||||
return _RFRN.wheelencoder_enabled;
|
||||
}
|
||||
|
||||
// log optical flow data
|
||||
void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset);
|
||||
|
||||
|
@ -66,6 +66,7 @@ struct log_RFRN {
|
||||
uint8_t fly_forward:1;
|
||||
uint8_t ahrs_airspeed_sensor_enabled:1;
|
||||
uint8_t opticalflow_enabled:1;
|
||||
uint8_t wheelencoder_enabled:1;
|
||||
uint8_t _end;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user