mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_MotorsHeli: Add To-Do. Swash setup hasn't seemed to work right for a while, this might be why. Confirm later.
This commit is contained in:
parent
a7f6a91827
commit
92bdf24dba
@ -527,6 +527,8 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll
|
|||||||
if (_heliflags.swash_initialised) {
|
if (_heliflags.swash_initialised) {
|
||||||
reset_swash();
|
reset_swash();
|
||||||
}
|
}
|
||||||
|
// To-Do: This equation seems to be wrong. It probably restricts swash movement so that swash setup doesn't work right.
|
||||||
|
// _collective_scalar should probably not be used or set to 1?
|
||||||
coll_out_scaled = coll_in * _collective_scalar + _rc_throttle.radio_min - 1000;
|
coll_out_scaled = coll_in * _collective_scalar + _rc_throttle.radio_min - 1000;
|
||||||
}else{ // regular flight mode
|
}else{ // regular flight mode
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user