mirror of https://github.com/ArduPilot/ardupilot
Copter: use new motors thrust linrisation, don't send air density ratio
This commit is contained in:
parent
ab4777de14
commit
be275e2cac
|
@ -163,7 +163,7 @@ void ModeTurtle::run()
|
|||
Vector2f input{sign_roll, sign_pitch};
|
||||
motors_input = input.normalized() * 0.5;
|
||||
// we bypass spin min and friends in the deadzone because we only want spin up when the sticks are moved
|
||||
motors_output = !is_zero(flip_power) ? motors->thrust_to_actuator(flip_power) : 0.0f;
|
||||
motors_output = !is_zero(flip_power) ? motors->thr_lin.thrust_to_actuator(flip_power) : 0.0f;
|
||||
}
|
||||
|
||||
// actually write values to the motors
|
||||
|
|
|
@ -6,8 +6,6 @@ void Copter::read_barometer(void)
|
|||
barometer.update();
|
||||
|
||||
baro_alt = barometer.get_altitude() * 100.0f;
|
||||
|
||||
motors->set_air_density_ratio(barometer.get_air_density_ratio());
|
||||
}
|
||||
|
||||
void Copter::init_rangefinder(void)
|
||||
|
|
Loading…
Reference in New Issue