mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Motors: fixed servo constructor for coax
This commit is contained in:
parent
4e5e301c4e
commit
6855899cbf
@ -27,7 +27,7 @@ public:
|
|||||||
/// Constructor
|
/// Constructor
|
||||||
AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
||||||
AP_MotorsMulticopter(loop_rate, speed_hz),
|
AP_MotorsMulticopter(loop_rate, speed_hz),
|
||||||
_servo1(CH_1), _servo2(CH_2), _servo3(CH_3), _servo4(CH_4)
|
_servo1(CH_NONE), _servo2(CH_NONE), _servo3(CH_NONE), _servo4(CH_NONE)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user