mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: stop using AHRS as conduit for Compass pointer
This commit is contained in:
parent
1d9bfdf8dd
commit
b5b4ec94c9
|
@ -58,7 +58,6 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
|
|||
_RFRN.lat = _home.lat;
|
||||
_RFRN.lng = _home.lng;
|
||||
_RFRN.alt = _home.alt;
|
||||
_RFRN.get_compass_is_null = AP::ahrs().get_compass() == nullptr;
|
||||
_RFRN.EAS2TAS = AP::baro().get_EAS2TAS();
|
||||
_RFRN.vehicle_class = ahrs.get_vehicle_class();
|
||||
_RFRN.fly_forward = ahrs.get_fly_forward();
|
||||
|
@ -257,15 +256,6 @@ void *AP_DAL::malloc_type(size_t size, Memory_Type mem_type) const
|
|||
return hal.util->malloc_type(size, AP_HAL::Util::Memory_Type(mem_type));
|
||||
}
|
||||
|
||||
|
||||
const AP_DAL_Compass *AP_DAL::get_compass() const
|
||||
{
|
||||
if (_RFRN.get_compass_is_null) {
|
||||
return nullptr;
|
||||
}
|
||||
return &_compass;
|
||||
}
|
||||
|
||||
// map core number for replay
|
||||
uint8_t AP_DAL::logging_core(uint8_t c) const
|
||||
{
|
||||
|
|
|
@ -141,18 +141,8 @@ public:
|
|||
}
|
||||
#endif
|
||||
|
||||
// this method *always* returns you the compass. This is in
|
||||
// constrast to get_compass, which only returns the compass once
|
||||
// the vehicle deigns to permit its use by the EKF.
|
||||
AP_DAL_Compass &compass() { return _compass; }
|
||||
|
||||
// this call replaces AP::ahrs()->get_compass(), whose return
|
||||
// result can be varied by the vehicle (typically by setting when
|
||||
// first reading is received). This is explicitly not
|
||||
// "AP_DAL_Compass &compass() { return _compass; } - but it should
|
||||
// change to be that.
|
||||
const AP_DAL_Compass *get_compass() const;
|
||||
|
||||
// random methods that AP_NavEKF3 wants to call on AHRS:
|
||||
bool airspeed_sensor_enabled(void) const {
|
||||
return _RFRN.ahrs_airspeed_sensor_enabled;
|
||||
|
|
|
@ -62,7 +62,7 @@ struct log_RFRN {
|
|||
uint8_t vehicle_class;
|
||||
uint8_t ekf_type;
|
||||
uint8_t armed:1;
|
||||
uint8_t get_compass_is_null:1;
|
||||
uint8_t unused:1; // was get_compass_is_null
|
||||
uint8_t fly_forward:1;
|
||||
uint8_t ahrs_airspeed_sensor_enabled:1;
|
||||
uint8_t opticalflow_enabled:1;
|
||||
|
|
Loading…
Reference in New Issue