Copter: remove manual_attitude and throttle flags

This commit is contained in:
Randy Mackay 2013-09-09 10:44:53 +09:00
parent b7579bb028
commit 942ba0476b
3 changed files with 3 additions and 34 deletions

View File

@ -380,8 +380,6 @@ static union {
struct {
uint8_t home_is_set : 1; // 0
uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE
uint8_t manual_attitude : 1; // 3
uint8_t manual_throttle : 1; // 4
uint8_t pre_arm_rc_check : 1; // 5 // true if rc input pre-arm checks have been completed successfully
uint8_t pre_arm_check : 1; // 6 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed

View File

@ -35,7 +35,7 @@ void roll_flip()
if (roll < 4500) {
// Roll control
roll_rate_target_bf = 40000 * flip_dir;
if(ap.manual_throttle){
if(throttle_mode == THROTTLE_MANUAL || throttle_mode == THROTTLE_MANUAL_TILT_COMPENSATED){
// increase throttle right before flip
set_throttle_out(g.rc_3.control_in + AAP_THR_INC, false);
}
@ -52,7 +52,7 @@ void roll_flip()
roll_rate_target_bf = 40000 * flip_dir;
#endif
// decrease throttle while inverted
if(ap.manual_throttle){
if(throttle_mode == THROTTLE_MANUAL || throttle_mode == THROTTLE_MANUAL_TILT_COMPENSATED){
set_throttle_out(g.rc_3.control_in - AAP_THR_DEC, false);
}
}else{
@ -68,7 +68,7 @@ void roll_flip()
// It will be handled by normal flight control loops
// increase throttle to gain any lost alitude
if(ap.manual_throttle){
if(throttle_mode == THROTTLE_MANUAL || throttle_mode == THROTTLE_MANUAL_TILT_COMPENSATED){
set_throttle_out(g.rc_3.control_in + AAP_THR_INC, false);
}
flip_timer++;

View File

@ -356,8 +356,6 @@ static bool set_mode(uint8_t mode)
switch(mode) {
case ACRO:
success = true;
ap.manual_throttle = true;
ap.manual_attitude = true;
set_yaw_mode(ACRO_YAW);
set_roll_pitch_mode(ACRO_RP);
set_throttle_mode(ACRO_THR);
@ -370,8 +368,6 @@ static bool set_mode(uint8_t mode)
case STABILIZE:
success = true;
ap.manual_throttle = true;
ap.manual_attitude = true;
set_yaw_mode(YAW_HOLD);
set_roll_pitch_mode(ROLL_PITCH_STABLE);
set_throttle_mode(THROTTLE_MANUAL_TILT_COMPENSATED);
@ -380,8 +376,6 @@ static bool set_mode(uint8_t mode)
case ALT_HOLD:
success = true;
ap.manual_throttle = false;
ap.manual_attitude = true;
set_yaw_mode(ALT_HOLD_YAW);
set_roll_pitch_mode(ALT_HOLD_RP);
set_throttle_mode(ALT_HOLD_THR);
@ -392,8 +386,6 @@ static bool set_mode(uint8_t mode)
// check we have a GPS and at least one mission command (note the home position is always command 0)
if ((GPS_ok() && g.command_total > 1) || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
// roll-pitch, throttle and yaw modes will all be set by the first nav command
init_commands(); // clear the command queues. will be reloaded when "run_autopilot" calls "update_commands" function
}
@ -402,8 +394,6 @@ static bool set_mode(uint8_t mode)
case CIRCLE:
if (GPS_ok() || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
set_roll_pitch_mode(CIRCLE_RP);
set_throttle_mode(CIRCLE_THR);
set_nav_mode(CIRCLE_NAV);
@ -414,8 +404,6 @@ static bool set_mode(uint8_t mode)
case LOITER:
if (GPS_ok() || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
set_yaw_mode(LOITER_YAW);
set_roll_pitch_mode(LOITER_RP);
set_throttle_mode(LOITER_THR);
@ -426,8 +414,6 @@ static bool set_mode(uint8_t mode)
case POSITION:
if (GPS_ok() || ignore_checks) {
success = true;
ap.manual_throttle = true;
ap.manual_attitude = false;
set_yaw_mode(POSITION_YAW);
set_roll_pitch_mode(POSITION_RP);
set_throttle_mode(POSITION_THR);
@ -438,8 +424,6 @@ static bool set_mode(uint8_t mode)
case GUIDED:
if (GPS_ok() || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
set_yaw_mode(get_wp_yaw_mode(false));
set_roll_pitch_mode(GUIDED_RP);
set_throttle_mode(GUIDED_THR);
@ -449,17 +433,12 @@ static bool set_mode(uint8_t mode)
case LAND:
success = true;
// To-Do: it is messy to set manual_attitude here because the do_land function is reponsible for setting the roll_pitch_mode
ap.manual_attitude = !GPS_ok();
ap.manual_throttle = false;
do_land(NULL); // land at current location
break;
case RTL:
if (GPS_ok() || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
do_RTL();
}
break;
@ -467,8 +446,6 @@ static bool set_mode(uint8_t mode)
case OF_LOITER:
if (g.optflow_enabled || ignore_checks) {
success = true;
ap.manual_throttle = false;
ap.manual_attitude = false;
set_yaw_mode(OF_LOITER_YAW);
set_roll_pitch_mode(OF_LOITER_RP);
set_throttle_mode(OF_LOITER_THR);
@ -481,8 +458,6 @@ static bool set_mode(uint8_t mode)
// See the defines for the enumerated values
case TOY_A:
success = true;
ap.manual_throttle = false;
ap.manual_attitude = true;
set_yaw_mode(YAW_TOY);
set_roll_pitch_mode(ROLL_PITCH_TOY);
set_throttle_mode(THROTTLE_AUTO);
@ -494,8 +469,6 @@ static bool set_mode(uint8_t mode)
case TOY_M:
success = true;
ap.manual_throttle = false;
ap.manual_attitude = true;
set_yaw_mode(YAW_TOY);
set_roll_pitch_mode(ROLL_PITCH_TOY);
set_nav_mode(NAV_NONE);
@ -504,8 +477,6 @@ static bool set_mode(uint8_t mode)
case SPORT:
success = true;
ap.manual_throttle = true;
ap.manual_attitude = true;
set_yaw_mode(SPORT_YAW);
set_roll_pitch_mode(SPORT_RP);
set_throttle_mode(SPORT_THR);