mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fixed default motor functions for single and coax copter
should be enabling motors 5 and 6 to match docs and SITL
This commit is contained in:
parent
f6c06496e2
commit
216bab4de4
|
@ -50,6 +50,10 @@ void AP_MotorsCoax::init(motor_frame_class frame_class, motor_frame_type frame_t
|
||||||
_servo3->set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
|
_servo3->set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
|
||||||
_servo4->set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
|
_servo4->set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
|
||||||
|
|
||||||
|
// allow mapping of motors 5 and 6
|
||||||
|
add_motor_num(CH_5);
|
||||||
|
add_motor_num(CH_6);
|
||||||
|
|
||||||
// record successful initialisation if what we setup was the desired frame_class
|
// record successful initialisation if what we setup was the desired frame_class
|
||||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
|
_flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
|
||||||
}
|
}
|
||||||
|
|
|
@ -53,8 +53,9 @@ void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame
|
||||||
_servo3->set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
_servo3->set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||||
_servo4->set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
_servo4->set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||||
|
|
||||||
// allow mapping of motor7
|
// allow mapping of motors 5 and 6
|
||||||
add_motor_num(CH_7);
|
add_motor_num(CH_5);
|
||||||
|
add_motor_num(CH_6);
|
||||||
|
|
||||||
// record successful initialisation if what we setup was the desired frame_class
|
// record successful initialisation if what we setup was the desired frame_class
|
||||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_SINGLE);
|
_flags.initialised_ok = (frame_class == MOTOR_FRAME_SINGLE);
|
||||||
|
|
Loading…
Reference in New Issue