Plane: fixed places that assumed mission command IDs are 8 bit

This commit is contained in:
Andrew Tridgell 2016-04-22 17:59:00 +10:00
parent 09c3c36c00
commit 07168c3db4
2 changed files with 2 additions and 2 deletions

View File

@ -485,7 +485,7 @@ void Plane::update_GPS_10Hz(void)
*/
void Plane::handle_auto_mode(void)
{
uint8_t nav_cmd_id;
uint16_t nav_cmd_id;
// we should be either running a mission or RTLing home
if (mission.state() == AP_Mission::MISSION_RUNNING) {

View File

@ -1176,7 +1176,7 @@ bool Plane::allow_reverse_thrust(void)
switch (control_mode) {
case AUTO:
{
uint8_t nav_cmd = mission.get_current_nav_cmd().id;
uint16_t nav_cmd = mission.get_current_nav_cmd().id;
// never allow reverse thrust during takeoff
if (nav_cmd == MAV_CMD_NAV_TAKEOFF) {