Plane: fixed places that assumed mission command IDs are 8 bit
This commit is contained in:
parent
09c3c36c00
commit
07168c3db4
@ -485,7 +485,7 @@ void Plane::update_GPS_10Hz(void)
|
|||||||
*/
|
*/
|
||||||
void Plane::handle_auto_mode(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
|
// we should be either running a mission or RTLing home
|
||||||
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||||
|
@ -1176,7 +1176,7 @@ bool Plane::allow_reverse_thrust(void)
|
|||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case AUTO:
|
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
|
// never allow reverse thrust during takeoff
|
||||||
if (nav_cmd == MAV_CMD_NAV_TAKEOFF) {
|
if (nav_cmd == MAV_CMD_NAV_TAKEOFF) {
|
||||||
|
Loading…
Reference in New Issue
Block a user