Copter: remove comments
This commit is contained in:
parent
70d1e53b74
commit
37bde3406d
@ -414,18 +414,11 @@ static bool set_mode(uint8_t mode)
|
||||
case POSITION:
|
||||
if (GPS_ok() || ignore_checks) {
|
||||
success = true;
|
||||
//set_yaw_mode(POSITION_YAW);
|
||||
//set_roll_pitch_mode(POSITION_RP);
|
||||
//set_throttle_mode(POSITION_THR);
|
||||
}
|
||||
break;
|
||||
|
||||
case GUIDED:
|
||||
success = guided_init(ignore_checks);
|
||||
//set_yaw_mode(get_wp_yaw_mode(false));
|
||||
//set_roll_pitch_mode(GUIDED_RP);
|
||||
//set_throttle_mode(GUIDED_THR);
|
||||
//set_nav_mode(GUIDED_NAV);
|
||||
break;
|
||||
|
||||
case LAND:
|
||||
@ -438,26 +431,14 @@ static bool set_mode(uint8_t mode)
|
||||
|
||||
case OF_LOITER:
|
||||
success = ofloiter_init(ignore_checks);
|
||||
//set_yaw_mode(OF_LOITER_YAW);
|
||||
//set_roll_pitch_mode(OF_LOITER_RP);
|
||||
//set_throttle_mode(OF_LOITER_THR);
|
||||
//set_nav_mode(OF_LOITER_NAV);
|
||||
break;
|
||||
|
||||
case DRIFT:
|
||||
success = drift_init(ignore_checks);
|
||||
//set_yaw_mode(YAW_DRIFT);
|
||||
//set_roll_pitch_mode(ROLL_PITCH_DRIFT);
|
||||
//set_nav_mode(NAV_NONE);
|
||||
//set_throttle_mode(DRIFT_THR);
|
||||
break;
|
||||
|
||||
case SPORT:
|
||||
success = sport_init(ignore_checks);
|
||||
//set_yaw_mode(SPORT_YAW);
|
||||
//set_roll_pitch_mode(SPORT_RP);
|
||||
//set_throttle_mode(SPORT_THR);
|
||||
//set_nav_mode(NAV_NONE);
|
||||
// reset acro angle targets to current attitude
|
||||
acro_roll = ahrs.roll_sensor;
|
||||
acro_pitch = ahrs.pitch_sensor;
|
||||
|
Loading…
Reference in New Issue
Block a user