Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/mode.cpp
Views: 1798
#include "Sub.h"12/*3constructor for Mode object4*/5Mode::Mode(void) :6g(sub.g),7g2(sub.g2),8inertial_nav(sub.inertial_nav),9ahrs(sub.ahrs),10motors(sub.motors),11channel_roll(sub.channel_roll),12channel_pitch(sub.channel_pitch),13channel_throttle(sub.channel_throttle),14channel_yaw(sub.channel_yaw),15channel_forward(sub.channel_forward),16channel_lateral(sub.channel_lateral),17position_control(&sub.pos_control),18attitude_control(&sub.attitude_control),19G_Dt(sub.G_Dt)20{ };2122// return the static controller object corresponding to supplied mode23Mode *Sub::mode_from_mode_num(const Mode::Number mode)24{25Mode *ret = nullptr;2627switch (mode) {28case Mode::Number::MANUAL:29ret = &mode_manual;30break;31case Mode::Number::STABILIZE:32ret = &mode_stabilize;33break;34case Mode::Number::ACRO:35ret = &mode_acro;36break;37case Mode::Number::ALT_HOLD:38ret = &mode_althold;39break;40case Mode::Number::SURFTRAK:41ret = &mode_surftrak;42break;43case Mode::Number::POSHOLD:44ret = &mode_poshold;45break;46case Mode::Number::AUTO:47ret = &mode_auto;48break;49case Mode::Number::GUIDED:50ret = &mode_guided;51break;52case Mode::Number::CIRCLE:53ret = &mode_circle;54break;55case Mode::Number::SURFACE:56ret = &mode_surface;57break;58case Mode::Number::MOTOR_DETECT:59ret = &mode_motordetect;60break;61default:62break;63}6465return ret;66}676869// set_mode - change flight mode and perform any necessary initialisation70// optional force parameter used to force the flight mode change (used only first time mode is set)71// returns true if mode was successfully set72// Some modes can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately73bool Sub::set_mode(Mode::Number mode, ModeReason reason)74{7576// return immediately if we are already in the desired mode77if (mode == control_mode) {78control_mode_reason = reason;79return true;80}8182Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode);83if (new_flightmode == nullptr) {84notify_no_such_mode((uint8_t)mode);85return false;86}8788if (new_flightmode->requires_GPS() &&89!sub.position_ok()) {90gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name());91LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));92return false;93}9495// check for valid altitude if old mode did not require it but new one does96// we only want to stop changing modes if it could make things worse97if (!sub.control_check_barometer() && // maybe use ekf_alt_ok() instead?98flightmode->has_manual_throttle() &&99!new_flightmode->has_manual_throttle()) {100gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s need alt estimate", new_flightmode->name());101LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));102return false;103}104105if (!new_flightmode->init(false)) {106gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed %s", new_flightmode->name());107LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));108return false;109}110111// perform any cleanup required by previous flight mode112exit_mode(flightmode, new_flightmode);113114// store previous flight mode115prev_control_mode = control_mode;116117// update flight mode118flightmode = new_flightmode;119control_mode = mode;120control_mode_reason = reason;121#if HAL_LOGGING_ENABLED122logger.Write_Mode((uint8_t)control_mode, reason);123#endif124gcs().send_message(MSG_HEARTBEAT);125126// update notify object127notify_flight_mode();128129// return success130return true;131}132133// exit_mode - high level call to organise cleanup as a flight mode is exited134void Sub::exit_mode(Mode::Number old_control_mode, Mode::Number new_control_mode)135{136// stop mission when we leave auto mode137if (old_control_mode == Mode::Number::AUTO) {138if (mission.state() == AP_Mission::MISSION_RUNNING) {139mission.stop();140}141#if HAL_MOUNT_ENABLED142camera_mount.set_mode_to_default();143#endif // HAL_MOUNT_ENABLED144}145}146147bool Sub::set_mode(const uint8_t new_mode, const ModeReason reason)148{149static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number");150return sub.set_mode(static_cast<Mode::Number>(new_mode), reason);151}152153// update_flight_mode - calls the appropriate attitude controllers based on flight mode154// called at 100hz or more155void Sub::update_flight_mode()156{157flightmode->run();158}159160// exit_mode - high level call to organise cleanup as a flight mode is exited161void Sub::exit_mode(Mode *&old_flightmode, Mode *&new_flightmode){162#if HAL_MOUNT_ENABLED163camera_mount.set_mode_to_default();164#endif // HAL_MOUNT_ENABLED165}166167// notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device168void Sub::notify_flight_mode()169{170AP_Notify::flags.autopilot_mode = flightmode->is_autopilot();171AP_Notify::flags.flight_mode = (uint8_t)control_mode;172notify.set_flight_mode_str(flightmode->name4());173}174175176// get_pilot_desired_angle_rates - transform pilot's roll pitch and yaw input into a desired lean angle rates177// returns desired angle rates in centi-degrees-per-second178void Mode::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out)179{180float rate_limit;181Vector3f rate_ef_level, rate_bf_level, rate_bf_request;182183// apply circular limit to pitch and roll inputs184float total_in = norm(pitch_in, roll_in);185186if (total_in > ROLL_PITCH_INPUT_MAX) {187float ratio = (float)ROLL_PITCH_INPUT_MAX / total_in;188roll_in *= ratio;189pitch_in *= ratio;190}191192// calculate roll, pitch rate requests193if (g.acro_expo <= 0) {194rate_bf_request.x = roll_in * g.acro_rp_p;195rate_bf_request.y = pitch_in * g.acro_rp_p;196} else {197// expo variables198float rp_in, rp_in3, rp_out;199200// range check expo201if (g.acro_expo > 1.0f) {202g.acro_expo.set(1.0f);203}204205// roll expo206rp_in = float(roll_in)/ROLL_PITCH_INPUT_MAX;207rp_in3 = rp_in*rp_in*rp_in;208rp_out = (g.acro_expo * rp_in3) + ((1 - g.acro_expo) * rp_in);209rate_bf_request.x = ROLL_PITCH_INPUT_MAX * rp_out * g.acro_rp_p;210211// pitch expo212rp_in = float(pitch_in)/ROLL_PITCH_INPUT_MAX;213rp_in3 = rp_in*rp_in*rp_in;214rp_out = (g.acro_expo * rp_in3) + ((1 - g.acro_expo) * rp_in);215rate_bf_request.y = ROLL_PITCH_INPUT_MAX * rp_out * g.acro_rp_p;216}217218// calculate yaw rate request219rate_bf_request.z = yaw_in * g.acro_yaw_p;220221// calculate earth frame rate corrections to pull the vehicle back to level while in ACRO mode222223if (g.acro_trainer != ACRO_TRAINER_DISABLED) {224// Calculate trainer mode earth frame rate command for roll225int32_t roll_angle = wrap_180_cd(ahrs.roll_sensor);226rate_ef_level.x = -constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll;227228// Calculate trainer mode earth frame rate command for pitch229int32_t pitch_angle = wrap_180_cd(ahrs.pitch_sensor);230rate_ef_level.y = -constrain_int32(pitch_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_pitch;231232// Calculate trainer mode earth frame rate command for yaw233rate_ef_level.z = 0;234235// Calculate angle limiting earth frame rate commands236if (g.acro_trainer == ACRO_TRAINER_LIMITED) {237if (roll_angle > sub.aparm.angle_max) {238rate_ef_level.x -= g.acro_balance_roll*(roll_angle-sub.aparm.angle_max);239} else if (roll_angle < -sub.aparm.angle_max) {240rate_ef_level.x -= g.acro_balance_roll*(roll_angle+sub.aparm.angle_max);241}242243if (pitch_angle > sub.aparm.angle_max) {244rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle-sub.aparm.angle_max);245} else if (pitch_angle < -sub.aparm.angle_max) {246rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle+sub.aparm.angle_max);247}248}249250// convert earth-frame level rates to body-frame level rates251attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level);252253// combine earth frame rate corrections with rate requests254if (g.acro_trainer == ACRO_TRAINER_LIMITED) {255rate_bf_request.x += rate_bf_level.x;256rate_bf_request.y += rate_bf_level.y;257rate_bf_request.z += rate_bf_level.z;258} else {259float acro_level_mix = constrain_float(1-MAX(MAX(abs(roll_in), abs(pitch_in)), abs(yaw_in))/4500.0, 0, 1)*ahrs.cos_pitch();260261// Scale leveling rates by stick input262rate_bf_level = rate_bf_level*acro_level_mix;263264// Calculate rate limit to prevent change of rate through inverted265rate_limit = fabsf(fabsf(rate_bf_request.x)-fabsf(rate_bf_level.x));266rate_bf_request.x += rate_bf_level.x;267rate_bf_request.x = constrain_float(rate_bf_request.x, -rate_limit, rate_limit);268269// Calculate rate limit to prevent change of rate through inverted270rate_limit = fabsf(fabsf(rate_bf_request.y)-fabsf(rate_bf_level.y));271rate_bf_request.y += rate_bf_level.y;272rate_bf_request.y = constrain_float(rate_bf_request.y, -rate_limit, rate_limit);273274// Calculate rate limit to prevent change of rate through inverted275rate_limit = fabsf(fabsf(rate_bf_request.z)-fabsf(rate_bf_level.z));276rate_bf_request.z += rate_bf_level.z;277rate_bf_request.z = constrain_float(rate_bf_request.z, -rate_limit, rate_limit);278}279}280281// hand back rate request282roll_out = rate_bf_request.x;283pitch_out = rate_bf_request.y;284yaw_out = rate_bf_request.z;285}286287288bool Mode::set_mode(Mode::Number mode, ModeReason reason)289{290return sub.set_mode(mode, reason);291}292293GCS_Sub &Mode::gcs()294{295return sub.gcs();296}297298299