mirror of https://github.com/ArduPilot/ardupilot
ACM: TradHeli
Fix to make update_throttle_cruise work with stab_throttle scaling.
This commit is contained in:
parent
c6537ae6e3
commit
083c451ec6
|
@ -1866,7 +1866,12 @@ void update_throttle_mode(void)
|
||||||
set_throttle_out(g.rc_3.control_in, false);
|
set_throttle_out(g.rc_3.control_in, false);
|
||||||
|
|
||||||
// update estimate of throttle cruise
|
// update estimate of throttle cruise
|
||||||
update_throttle_cruise(g.rc_3.control_in);
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
update_throttle_cruise(motors.coll_out);
|
||||||
|
#else
|
||||||
|
update_throttle_cruise(g.rc_3.control_in);
|
||||||
|
#endif //HELI_FRAME
|
||||||
|
|
||||||
|
|
||||||
// check if we've taken off yet
|
// check if we've taken off yet
|
||||||
if (!ap.takeoff_complete && motors.armed()) {
|
if (!ap.takeoff_complete && motors.armed()) {
|
||||||
|
@ -1886,7 +1891,11 @@ void update_throttle_mode(void)
|
||||||
set_throttle_out(g.rc_3.control_in, true);
|
set_throttle_out(g.rc_3.control_in, true);
|
||||||
|
|
||||||
// update estimate of throttle cruise
|
// update estimate of throttle cruise
|
||||||
update_throttle_cruise(g.rc_3.control_in);
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
update_throttle_cruise(motors.coll_out);
|
||||||
|
#else
|
||||||
|
update_throttle_cruise(g.rc_3.control_in);
|
||||||
|
#endif //HELI_FRAME
|
||||||
|
|
||||||
if (!ap.takeoff_complete && motors.armed()) {
|
if (!ap.takeoff_complete && motors.armed()) {
|
||||||
if (g.rc_3.control_in > g.throttle_cruise) {
|
if (g.rc_3.control_in > g.throttle_cruise) {
|
||||||
|
|
|
@ -699,7 +699,6 @@ get_of_pitch(int32_t input_pitch)
|
||||||
* yaw controllers
|
* yaw controllers
|
||||||
*************************************************************/
|
*************************************************************/
|
||||||
|
|
||||||
// update_throttle_cruise - update throttle cruise if necessary
|
|
||||||
static void get_look_ahead_yaw(int16_t pilot_yaw)
|
static void get_look_ahead_yaw(int16_t pilot_yaw)
|
||||||
{
|
{
|
||||||
// Commanded Yaw to automatically look ahead.
|
// Commanded Yaw to automatically look ahead.
|
||||||
|
|
|
@ -445,7 +445,7 @@ void AP_MotorsHeli::init_swash()
|
||||||
// collective: 0 ~ 1000
|
// collective: 0 ~ 1000
|
||||||
// yaw: -4500 ~ 4500
|
// yaw: -4500 ~ 4500
|
||||||
//
|
//
|
||||||
void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_out, int16_t yaw_out)
|
void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_in, int16_t yaw_out)
|
||||||
{
|
{
|
||||||
int16_t yaw_offset = 0;
|
int16_t yaw_offset = 0;
|
||||||
int16_t coll_out_scaled;
|
int16_t coll_out_scaled;
|
||||||
|
@ -455,7 +455,7 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll
|
||||||
if( _swash_initialised ) {
|
if( _swash_initialised ) {
|
||||||
reset_swash();
|
reset_swash();
|
||||||
}
|
}
|
||||||
coll_out_scaled = coll_out * _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
|
||||||
|
|
||||||
// check if we need to reinitialise the swash
|
// check if we need to reinitialise the swash
|
||||||
|
@ -475,7 +475,7 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll
|
||||||
pitch_out = constrain(pitch_out, (int16_t)-pitch_max, (int16_t)pitch_max);
|
pitch_out = constrain(pitch_out, (int16_t)-pitch_max, (int16_t)pitch_max);
|
||||||
|
|
||||||
// scale collective pitch
|
// scale collective pitch
|
||||||
coll_out = constrain(coll_out, 0, 1000);
|
coll_out = constrain(coll_in, 0, 1000);
|
||||||
if (stab_throttle){
|
if (stab_throttle){
|
||||||
coll_out = coll_out * _stab_throttle_scalar + stab_col_min*10;
|
coll_out = coll_out * _stab_throttle_scalar + stab_col_min*10;
|
||||||
}
|
}
|
||||||
|
|
|
@ -106,7 +106,7 @@ public:
|
||||||
AP_Int8 stab_col_min; // collective pitch minimum in Stabilize Mode
|
AP_Int8 stab_col_min; // collective pitch minimum in Stabilize Mode
|
||||||
AP_Int8 stab_col_max; // collective pitch maximum in Stabilize Mode
|
AP_Int8 stab_col_max; // collective pitch maximum in Stabilize Mode
|
||||||
bool stab_throttle; // true if we are in Stabilize Mode for reduced Swash Range
|
bool stab_throttle; // true if we are in Stabilize Mode for reduced Swash Range
|
||||||
|
AP_Int16 coll_out; // returns the actual collective in use to the main code
|
||||||
|
|
||||||
// init
|
// init
|
||||||
void Init();
|
void Init();
|
||||||
|
@ -141,7 +141,7 @@ public:
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// heli_move_swash - moves swash plate to attitude of parameters passed in
|
// heli_move_swash - moves swash plate to attitude of parameters passed in
|
||||||
void move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_out, int16_t yaw_out);
|
void move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_in, int16_t yaw_out);
|
||||||
|
|
||||||
// reset_swash - free up swash for maximum movements. Used for set-up
|
// reset_swash - free up swash for maximum movements. Used for set-up
|
||||||
void reset_swash();
|
void reset_swash();
|
||||||
|
|
Loading…
Reference in New Issue