mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_InertialSensor: move constructor into cpp
This commit is contained in:
parent
c63c4f22e2
commit
7277d4934d
@ -52,6 +52,10 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = {
|
|||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
AP_InertialSensor::AP_InertialSensor() {
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
AP_InertialSensor::init( Start_style style,
|
AP_InertialSensor::init( Start_style style,
|
||||||
Sample_rate sample_rate,
|
Sample_rate sample_rate,
|
||||||
|
@ -22,9 +22,7 @@
|
|||||||
class AP_InertialSensor
|
class AP_InertialSensor
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
AP_InertialSensor() {
|
AP_InertialSensor();
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
|
||||||
}
|
|
||||||
|
|
||||||
enum Start_style {
|
enum Start_style {
|
||||||
COLD_START = 0,
|
COLD_START = 0,
|
||||||
|
Loading…
Reference in New Issue
Block a user