navigator: fix wrong altitude after takeoff

This change fixes a wrong behaviour when a takeoff command is sent.

An example:
- MIS_TAKEOFF_ALT set to 10 meters
- Takeoff command with alt setpoint of 2 meters

Old behaviour:
1. Climb to 10 meters -> takeoff WP reached
2. Go to setpoint at 2 meters

New behaviour:
1. Climb to 10 meters and stay there but notify that altitude was
   overridden.
This commit is contained in:
Julian Oes
2016-10-23 12:34:30 +02:00
committed by Lorenz Meier
parent 032f4df3de
commit 82f27884df
3 changed files with 37 additions and 19 deletions

View File

@@ -107,7 +107,7 @@ protected:
/**
* Set a takeoff mission item
*/
void set_takeoff_item(struct mission_item_s *item, float min_clearance = -1.0f, float min_pitch = 0.0f);
void set_takeoff_item(struct mission_item_s *item, float abs_altitude, float min_pitch = 0.0f);
/**
* Set a land mission item