mirror of https://github.com/ArduPilot/ardupilot
Copter: land_state uses enum
This resolves a Covarity warning related to initialisation (that was not really a problem) but it is better form anyway
This commit is contained in:
parent
3c87f67212
commit
728e8f8f56
|
@ -349,7 +349,7 @@ private:
|
|||
int32_t home_distance;
|
||||
// distance between plane and next waypoint in cm.
|
||||
uint32_t wp_distance;
|
||||
uint8_t land_state; // records state of land (flying to location, descending)
|
||||
LandStateType land_state = LandStateType_FlyToLocation; // records state of land (flying to location, descending)
|
||||
|
||||
// Auto
|
||||
AutoMode auto_mode; // controls which auto controller is run
|
||||
|
|
|
@ -323,7 +323,7 @@ void Copter::do_land(const AP_Mission::Mission_Command& cmd)
|
|||
// if location provided we fly to that location at current altitude
|
||||
if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
|
||||
// set state to fly to location
|
||||
land_state = LAND_STATE_FLY_TO_LOCATION;
|
||||
land_state = LandStateType_FlyToLocation;
|
||||
|
||||
// convert to location class
|
||||
Location_Class target_loc(cmd.content.location);
|
||||
|
@ -342,7 +342,7 @@ void Copter::do_land(const AP_Mission::Mission_Command& cmd)
|
|||
auto_wp_start(target_loc);
|
||||
}else{
|
||||
// set landing state
|
||||
land_state = LAND_STATE_DESCENDING;
|
||||
land_state = LandStateType_Descending;
|
||||
|
||||
// initialise landing controller
|
||||
auto_land_start();
|
||||
|
@ -600,8 +600,8 @@ bool Copter::verify_land()
|
|||
{
|
||||
bool retval = false;
|
||||
|
||||
switch( land_state ) {
|
||||
case LAND_STATE_FLY_TO_LOCATION:
|
||||
switch (land_state) {
|
||||
case LandStateType_FlyToLocation:
|
||||
// check if we've reached the location
|
||||
if (wp_nav.reached_wp_destination()) {
|
||||
// get destination so we can use it for loiter target
|
||||
|
@ -611,11 +611,11 @@ bool Copter::verify_land()
|
|||
auto_land_start(dest);
|
||||
|
||||
// advance to next state
|
||||
land_state = LAND_STATE_DESCENDING;
|
||||
land_state = LandStateType_Descending;
|
||||
}
|
||||
break;
|
||||
|
||||
case LAND_STATE_DESCENDING:
|
||||
case LandStateType_Descending:
|
||||
// rely on THROTTLE_LAND mode to correctly update landing status
|
||||
retval = ap.land_complete;
|
||||
break;
|
||||
|
|
|
@ -271,9 +271,10 @@ enum ThrowModeType {
|
|||
ThrowType_Drop = 1
|
||||
};
|
||||
|
||||
// LAND state
|
||||
#define LAND_STATE_FLY_TO_LOCATION 0
|
||||
#define LAND_STATE_DESCENDING 1
|
||||
enum LandStateType {
|
||||
LandStateType_FlyToLocation = 0,
|
||||
LandStateType_Descending = 1
|
||||
};
|
||||
|
||||
// Logging parameters
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
|
|
Loading…
Reference in New Issue