Plane: Use tecs to control the throttle during takeoff
This commit is contained in:
parent
04e9141881
commit
78a3ce46b9
@ -1195,9 +1195,8 @@ static void handle_auto_mode(void)
|
|||||||
case MAV_CMD_NAV_TAKEOFF:
|
case MAV_CMD_NAV_TAKEOFF:
|
||||||
takeoff_calc_roll();
|
takeoff_calc_roll();
|
||||||
takeoff_calc_pitch();
|
takeoff_calc_pitch();
|
||||||
|
calc_throttle();
|
||||||
// max throttle for takeoff
|
|
||||||
channel_throttle->servo_out = takeoff_throttle();
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_NAV_LAND:
|
case MAV_CMD_NAV_LAND:
|
||||||
|
@ -805,7 +805,11 @@ static void set_servos(void)
|
|||||||
min_throttle = 0;
|
min_throttle = 0;
|
||||||
}
|
}
|
||||||
if (control_mode == AUTO && flight_stage == AP_SpdHgtControl::FLIGHT_TAKEOFF) {
|
if (control_mode == AUTO && flight_stage == AP_SpdHgtControl::FLIGHT_TAKEOFF) {
|
||||||
max_throttle = takeoff_throttle();
|
if(aparm.takeoff_throttle_max != 0) {
|
||||||
|
max_throttle = aparm.takeoff_throttle_max;
|
||||||
|
} else {
|
||||||
|
max_throttle = aparm.throttle_max;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
|
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
|
||||||
min_throttle,
|
min_throttle,
|
||||||
|
@ -464,7 +464,6 @@ public:
|
|||||||
AP_Float takeoff_tdrag_speed1;
|
AP_Float takeoff_tdrag_speed1;
|
||||||
AP_Float takeoff_rotate_speed;
|
AP_Float takeoff_rotate_speed;
|
||||||
AP_Int8 takeoff_throttle_slewrate;
|
AP_Int8 takeoff_throttle_slewrate;
|
||||||
AP_Int8 takeoff_throttle_max;
|
|
||||||
AP_Int8 level_roll_limit;
|
AP_Int8 level_roll_limit;
|
||||||
AP_Int8 flapin_channel;
|
AP_Int8 flapin_channel;
|
||||||
AP_Int8 flaperon_output;
|
AP_Int8 flaperon_output;
|
||||||
|
@ -453,7 +453,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Range: 0 100
|
// @Range: 0 100
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(takeoff_throttle_max, "TKOFF_THR_MAX", 0),
|
ASCALAR(takeoff_throttle_max, "TKOFF_THR_MAX", 0),
|
||||||
|
|
||||||
// @Param: THR_SLEWRATE
|
// @Param: THR_SLEWRATE
|
||||||
// @DisplayName: Throttle slew rate
|
// @DisplayName: Throttle slew rate
|
||||||
|
@ -170,13 +170,3 @@ return_zero:
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
return throttle percentage for takeoff
|
|
||||||
*/
|
|
||||||
static uint8_t takeoff_throttle(void)
|
|
||||||
{
|
|
||||||
if (g.takeoff_throttle_max != 0) {
|
|
||||||
return g.takeoff_throttle_max;
|
|
||||||
}
|
|
||||||
return aparm.throttle_max;
|
|
||||||
}
|
|
||||||
|
Loading…
Reference in New Issue
Block a user