mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMatrix: do not set limits in output_min
This commit is contained in:
parent
3fef60da45
commit
d0c6d087a5
|
@ -88,13 +88,7 @@ void AP_MotorsMatrix::output_min()
|
||||||
{
|
{
|
||||||
int8_t i;
|
int8_t i;
|
||||||
|
|
||||||
// set limits flags
|
// send output to each motor
|
||||||
limit.roll_pitch = true;
|
|
||||||
limit.yaw = true;
|
|
||||||
limit.throttle_lower = true;
|
|
||||||
limit.throttle_upper = false;
|
|
||||||
|
|
||||||
// fill the motor_out[] array for HIL use and send minimum value to each motor
|
|
||||||
hal.rcout->cork();
|
hal.rcout->cork();
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||||
if( motor_enabled[i] ) {
|
if( motor_enabled[i] ) {
|
||||||
|
|
Loading…
Reference in New Issue