mirror of https://github.com/ArduPilot/ardupilot
AP_WheelEncoder: remove un-needed initialisations
Should only be created statically
This commit is contained in:
parent
57bc4d8736
commit
d3877bf2d0
|
@ -139,14 +139,9 @@ const AP_Param::GroupInfo AP_WheelEncoder::var_info[] = {
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_WheelEncoder::AP_WheelEncoder(void) :
|
AP_WheelEncoder::AP_WheelEncoder(void)
|
||||||
num_instances(0)
|
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
// init state and drivers
|
|
||||||
memset(state, 0, sizeof(state));
|
|
||||||
memset(drivers, 0, sizeof(drivers));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise the AP_WheelEncoder class.
|
// initialise the AP_WheelEncoder class.
|
||||||
|
|
Loading…
Reference in New Issue