mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_InertialSensor: updates for new AP_Param API
This commit is contained in:
parent
62e396167a
commit
c064becf28
@ -52,10 +52,6 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_InertialSensor::AP_InertialSensor()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
AP_InertialSensor::init( Start_style style,
|
||||
Sample_rate sample_rate,
|
||||
|
@ -22,7 +22,9 @@
|
||||
class AP_InertialSensor
|
||||
{
|
||||
public:
|
||||
AP_InertialSensor();
|
||||
AP_InertialSensor() {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
enum Start_style {
|
||||
COLD_START = 0,
|
||||
|
Loading…
Reference in New Issue
Block a user