Copter: remove Position mode

This commit is contained in:
Randy Mackay 2014-01-29 13:43:42 +09:00 committed by Andrew Tridgell
parent c632211c8c
commit ef666c73ab
5 changed files with 6 additions and 38 deletions

View File

@ -174,9 +174,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break; break;
case POSITION:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;
case SPORT: case SPORT:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
break; break;

View File

@ -315,42 +315,42 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FLTMODE1 // @Param: FLTMODE1
// @DisplayName: Flight Mode 1 // @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230 // @Description: Flight mode when Channel 5 pwm is <= 1230
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1), GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
// @Param: FLTMODE2 // @Param: FLTMODE2
// @DisplayName: Flight Mode 2 // @DisplayName: Flight Mode 2
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360 // @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2), GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
// @Param: FLTMODE3 // @Param: FLTMODE3
// @DisplayName: Flight Mode 3 // @DisplayName: Flight Mode 3
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490 // @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3), GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
// @Param: FLTMODE4 // @Param: FLTMODE4
// @DisplayName: Flight Mode 4 // @DisplayName: Flight Mode 4
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620 // @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4), GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
// @Param: FLTMODE5 // @Param: FLTMODE5
// @DisplayName: Flight Mode 5 // @DisplayName: Flight Mode 5
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749 // @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5), GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
// @Param: FLTMODE6 // @Param: FLTMODE6
// @DisplayName: Flight Mode 6 // @DisplayName: Flight Mode 6
// @Description: Flight mode when Channel 5 pwm is >=1750 // @Description: Flight mode when Channel 5 pwm is >=1750
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard // @User: Standard
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6), GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),

View File

@ -631,24 +631,6 @@
# define LOITER_NAV NAV_LOITER # define LOITER_NAV NAV_LOITER
#endif #endif
// POSITION Mode
#ifndef POSITION_YAW
# define POSITION_YAW YAW_HOLD
#endif
#ifndef POSITION_RP
# define POSITION_RP ROLL_PITCH_LOITER
#endif
#ifndef POSITION_THR
# define POSITION_THR THROTTLE_MANUAL_TILT_COMPENSATED
#endif
#ifndef POSITION_NAV
# define POSITION_NAV NAV_LOITER
#endif
// RTL Mode // RTL Mode
// Note: RTL Yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter // Note: RTL Yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter
#ifndef RTL_RP #ifndef RTL_RP

View File

@ -123,7 +123,6 @@
#define LOITER 5 // Hold a single location #define LOITER 5 // Hold a single location
#define RTL 6 // AUTO control #define RTL 6 // AUTO control
#define CIRCLE 7 // AUTO control #define CIRCLE 7 // AUTO control
#define POSITION 8 // AUTO control
#define LAND 9 // AUTO control #define LAND 9 // AUTO control
#define OF_LOITER 10 // Hold a single location using optical flow sensor #define OF_LOITER 10 // Hold a single location using optical flow sensor
#define DRIFT 11 // DRIFT mode (Note: 12 is no longer used) #define DRIFT 11 // DRIFT mode (Note: 12 is no longer used)

View File

@ -346,7 +346,6 @@ static bool mode_requires_GPS(uint8_t mode) {
case LOITER: case LOITER:
case RTL: case RTL:
case CIRCLE: case CIRCLE:
case POSITION:
case DRIFT: case DRIFT:
return true; return true;
default: default:
@ -411,12 +410,6 @@ static bool set_mode(uint8_t mode)
success = loiter_init(ignore_checks); success = loiter_init(ignore_checks);
break; break;
case POSITION:
if (GPS_ok() || ignore_checks) {
success = true;
}
break;
case GUIDED: case GUIDED:
success = guided_init(ignore_checks); success = guided_init(ignore_checks);
break; break;
@ -568,9 +561,6 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
case CIRCLE: case CIRCLE:
port->print_P(PSTR("CIRCLE")); port->print_P(PSTR("CIRCLE"));
break; break;
case POSITION:
port->print_P(PSTR("POSITION"));
break;
case LAND: case LAND:
port->print_P(PSTR("LAND")); port->print_P(PSTR("LAND"));
break; break;