mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: use 4 degrees if zero takeoff pitch
This commit is contained in:
parent
953efa9b6c
commit
0cc165308d
@ -320,6 +320,10 @@ void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
|
||||
set_next_WP(cmd.content.location);
|
||||
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
|
||||
auto_state.takeoff_pitch_cd = (int16_t)cmd.p1 * 100;
|
||||
if (auto_state.takeoff_pitch_cd <= 0) {
|
||||
// if the mission doesn't specify a pitch use 4 degrees
|
||||
auto_state.takeoff_pitch_cd = 400;
|
||||
}
|
||||
auto_state.takeoff_altitude_rel_cm = next_WP_loc.alt - home.alt;
|
||||
next_WP_loc.lat = home.lat + 10;
|
||||
next_WP_loc.lng = home.lng + 10;
|
||||
|
Loading…
Reference in New Issue
Block a user