mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: move VehicleClass handling to AHRS frontend
.... and renaming the enumeration while we're at it
This commit is contained in:
parent
1cfd9f57ce
commit
fc6d8222e7
|
@ -59,7 +59,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
|
||||||
_RFRN.lng = _home.lng;
|
_RFRN.lng = _home.lng;
|
||||||
_RFRN.alt = _home.alt;
|
_RFRN.alt = _home.alt;
|
||||||
_RFRN.EAS2TAS = AP::baro().get_EAS2TAS();
|
_RFRN.EAS2TAS = AP::baro().get_EAS2TAS();
|
||||||
_RFRN.vehicle_class = ahrs.get_vehicle_class();
|
_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();
|
||||||
_RFRN.fly_forward = ahrs.get_fly_forward();
|
_RFRN.fly_forward = ahrs.get_fly_forward();
|
||||||
_RFRN.takeoff_expected = ahrs.get_takeoff_expected();
|
_RFRN.takeoff_expected = ahrs.get_takeoff_expected();
|
||||||
_RFRN.touchdown_expected = ahrs.get_touchdown_expected();
|
_RFRN.touchdown_expected = ahrs.get_touchdown_expected();
|
||||||
|
|
Loading…
Reference in New Issue