Browse Source

AP_Vehicle: add custom rotations lib

apm_2208
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
f15c84bdac
  1. 6
      libraries/AP_Vehicle/AP_Vehicle.cpp
  2. 3
      libraries/AP_Vehicle/AP_Vehicle.h

6
libraries/AP_Vehicle/AP_Vehicle.cpp

@ -73,6 +73,10 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { @@ -73,6 +73,10 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
AP_SUBGROUPINFO(airspeed, "ARSPD", 10, AP_Vehicle, AP_Airspeed),
#endif
// @Group: CUST_ROT
// @Path: ../AP_CustomRotations/AP_CustomRotations.cpp
AP_SUBGROUPINFO(custom_rotations, "CUST_ROT", 11, AP_Vehicle, AP_CustomRotations),
AP_GROUPEND
};
@ -204,6 +208,8 @@ void AP_Vehicle::setup() @@ -204,6 +208,8 @@ void AP_Vehicle::setup()
efi.init();
#endif
custom_rotations.init();
gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready");
}

3
libraries/AP_Vehicle/AP_Vehicle.h

@ -51,6 +51,7 @@ @@ -51,6 +51,7 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#endif
#include <AP_CustomRotations/AP_CustomRotations.h>
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
@ -413,6 +414,8 @@ private: @@ -413,6 +414,8 @@ private:
bool done_safety_init;
uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask
AP_CustomRotations custom_rotations;
};
namespace AP {

Loading…
Cancel
Save