Copter: rename stop to brake

This commit is contained in:
Randy Mackay 2015-05-17 12:22:20 +09:00
parent 0077cac1b7
commit 7acdcd8905
5 changed files with 23 additions and 20 deletions

View File

@ -63,7 +63,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
case GUIDED:
case CIRCLE:
case POSHOLD:
case STOP:
case BRAKE:
base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
// APM does in any mode, as that is defined as "system finds its own goal
@ -174,7 +174,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
case LAND:
case OF_LOITER:
case POSHOLD:
case STOP:
case BRAKE:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;

View File

@ -580,8 +580,8 @@
//////////////////////////////////////////////////////////////////////////////
// Stop mode defaults
//
#ifndef STOP_MODE_DECEL_RATE
# define STOP_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Stop Mode
#ifndef BRAKE_MODE_DECEL_RATE
# define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode
#endif
//////////////////////////////////////////////////////////////////////////////

View File

@ -1,11 +1,11 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* control_stop.pde - init and run calls for stop flight mode
* control_brake.pde - init and run calls for brake flight mode
*/
// stop_init - initialise stop controller
static bool stop_init(bool ignore_checks)
// brake_init - initialise brake controller
static bool brake_init(bool ignore_checks)
{
if (position_ok() || optflow_position_ok() || ignore_checks) {
@ -13,11 +13,11 @@ static bool stop_init(bool ignore_checks)
wp_nav.clear_pilot_desired_acceleration();
// set target to current position
wp_nav.init_stop_target(STOP_MODE_DECEL_RATE);
wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE);
// initialize vertical speed and acceleration
pos_control.set_speed_z(0, 0);
pos_control.set_accel_z(STOP_MODE_DECEL_RATE);
pos_control.set_accel_z(BRAKE_MODE_DECEL_RATE);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
@ -28,16 +28,16 @@ static bool stop_init(bool ignore_checks)
}
}
// stop_run - runs the stop controller
// brake_run - runs the brake controller
// should be called at 100hz or more
static void stop_run()
static void brake_run()
{
float target_yaw_rate = 0;
float target_climb_rate = 0;
// if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) {
wp_nav.init_stop_target(STOP_MODE_DECEL_RATE);
wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(0)-throttle_average);
return;
@ -52,8 +52,8 @@ static void stop_run()
// ToDo: What do we do here?
}
// run stop controller
wp_nav.update_stop(ekfGndSpdLimit, ekfNavVelGainScaler);
// run brake controller
wp_nav.update_brake(ekfGndSpdLimit, ekfNavVelGainScaler);
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);

View File

@ -106,7 +106,7 @@ enum autopilot_modes {
FLIP = 14, // automatically flip the vehicle on the roll axis
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
STOP = 17 // full-stop using inertial/GPS system, no pilot input
BRAKE = 17 // full-brake using inertial/GPS system, no pilot input
};
// Tuning enumeration

View File

@ -89,8 +89,8 @@ static bool set_mode(uint8_t mode)
break;
#endif
case STOP:
success = stop_init(ignore_checks);
case BRAKE:
success = brake_init(ignore_checks);
break;
default:
@ -202,8 +202,8 @@ static void update_flight_mode()
break;
#endif
case STOP:
stop_run();
case BRAKE:
brake_run();
break;
}
}
@ -254,7 +254,7 @@ static bool mode_requires_GPS(uint8_t mode) {
case CIRCLE:
case DRIFT:
case POSHOLD:
case STOP:
case BRAKE:
return true;
default:
return false;
@ -355,6 +355,9 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
case POSHOLD:
port->print_P(PSTR("POSHOLD"));
break;
case BRAKE:
port->print_P(PSTR("BRAKE"));
break;
default:
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
break;