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/ArduCopter/heli.cpp
Views: 1798
#include "Copter.h"12// Traditional helicopter variables and functions34#if FRAME_CONFIG == HELI_FRAME56#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN7#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 250 // we are in "dynamic flight" when the speed is over 2.5m/s for 2 seconds8#endif910// counter to control dynamic flight profile11static int8_t heli_dynamic_flight_counter;1213// heli_init - perform any special initialisation required for the tradheli14void Copter::heli_init()15{16// pre-load stab col values as mode is initialized as Stabilize, but stabilize_init() function is not run on start-up.17input_manager.set_use_stab_col(true);18input_manager.set_stab_col_ramp(1.0);19}2021// heli_check_dynamic_flight - updates the dynamic_flight flag based on our horizontal velocity22// should be called at 50hz23void Copter::check_dynamic_flight(void)24{25if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ||26flightmode->is_landing()) {27heli_dynamic_flight_counter = 0;28heli_flags.dynamic_flight = false;29return;30}3132bool moving = false;3334// with GPS lock use inertial nav to determine if we are moving35if (position_ok()) {36// get horizontal speed37const float speed = inertial_nav.get_speed_xy_cms();38moving = (speed >= HELI_DYNAMIC_FLIGHT_SPEED_MIN);39} else {40// with no GPS lock base it on throttle and forward lean angle41moving = (motors->get_throttle() > 0.8f || ahrs.pitch_sensor < -1500);42}4344#if AP_RANGEFINDER_ENABLED45if (!moving && rangefinder_state.enabled && rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) {46// when we are more than 2m from the ground with good47// rangefinder lock consider it to be dynamic flight48moving = (rangefinder.distance_cm_orient(ROTATION_PITCH_270) > 200);49}50#endif5152if (moving) {53// if moving for 2 seconds, set the dynamic flight flag54if (!heli_flags.dynamic_flight) {55heli_dynamic_flight_counter++;56if (heli_dynamic_flight_counter >= 100) {57heli_flags.dynamic_flight = true;58heli_dynamic_flight_counter = 100;59}60}61} else {62// if not moving for 2 seconds, clear the dynamic flight flag63if (heli_flags.dynamic_flight) {64if (heli_dynamic_flight_counter > 0) {65heli_dynamic_flight_counter--;66} else {67heli_flags.dynamic_flight = false;68}69}70}71}7273// update_heli_control_dynamics - pushes several important factors up into AP_MotorsHeli.74// should be run between the rate controller and the servo updates.75void Copter::update_heli_control_dynamics(void)76{7778if (!motors->using_leaky_integrator()) {79//turn off leaky_I80attitude_control->use_leaky_i(false);81if (ap.land_complete || ap.land_complete_maybe) {82motors->set_land_complete(true);83} else {84motors->set_land_complete(false);85}86} else {87// Use Leaky_I if we are not moving fast88attitude_control->use_leaky_i(!heli_flags.dynamic_flight);89motors->set_land_complete(false);90}9192if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))) {93// if we are landed or there is no rotor power demanded, decrement slew scalar94hover_roll_trim_scalar_slew--;95} else {96// if we are not landed and motor power is demanded, increment slew scalar97hover_roll_trim_scalar_slew++;98}99hover_roll_trim_scalar_slew = constrain_int16(hover_roll_trim_scalar_slew, 0, scheduler.get_loop_rate_hz());100101// set hover roll trim scalar, will ramp from 0 to 1 over 1 second after we think helicopter has taken off102attitude_control->set_hover_roll_trim_scalar((float) hover_roll_trim_scalar_slew/(float) scheduler.get_loop_rate_hz());103}104105bool Copter::should_use_landing_swash() const106{107if (flightmode->has_manual_throttle() ||108flightmode->mode_number() == Mode::Number::DRIFT ||109attitude_control->get_inverted_flight()) {110// manual modes or modes using inverted flight uses full swash range111return false;112}113if (flightmode->is_landing()) {114// landing with non-manual throttle mode always uses limit swash range115return true;116}117if (ap.land_complete) {118// when landed in non-manual throttle mode limit swash range119return true;120}121if (!ap.auto_armed) {122// when waiting to takeoff in non-manual throttle mode limit swash range123return true;124}125if (!heli_flags.dynamic_flight) {126// Just in case we are unsure of being in non-manual throttle127// mode, limit swash range in low speed and hovering flight.128// This will catch any non-manual throttle mode attempting a129// landing and driving the collective too low before the land130// complete flag is set.131return true;132}133return false;134}135136// heli_update_landing_swash - sets swash plate flag so higher minimum is used when landed or landing137// should be called soon after update_land_detector in main code138void Copter::heli_update_landing_swash()139{140motors->set_collective_for_landing(should_use_landing_swash());141update_collective_low_flag(channel_throttle->get_control_in());142}143144// convert motor interlock switch's position to desired rotor speed expressed as a value from 0 to 1145// returns zero if motor interlock auxiliary switch hasn't been defined146float Copter::get_pilot_desired_rotor_speed() const147{148RC_Channel *rc_ptr = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK);149if (rc_ptr != nullptr) {150rc_ptr->set_range(1000);151return (float)rc_ptr->get_control_in() * 0.001f;152}153return 0.0f;154}155156// heli_update_rotor_speed_targets - reads pilot input and passes new rotor speed targets to heli motors object157void Copter::heli_update_rotor_speed_targets()158{159// get rotor control method160uint8_t rsc_control_mode = motors->get_rsc_mode();161162switch (rsc_control_mode) {163case ROTOR_CONTROL_MODE_PASSTHROUGH:164// pass through pilot desired rotor speed from the RC165if (get_pilot_desired_rotor_speed() > 0.01) {166ap.motor_interlock_switch = true;167motors->set_desired_rotor_speed(get_pilot_desired_rotor_speed());168} else {169ap.motor_interlock_switch = false;170motors->set_desired_rotor_speed(0.0f);171}172break;173case ROTOR_CONTROL_MODE_SETPOINT:174case ROTOR_CONTROL_MODE_THROTTLECURVE:175case ROTOR_CONTROL_MODE_AUTOTHROTTLE:176if (motors->get_interlock()) {177motors->set_desired_rotor_speed(motors->get_rsc_setpoint());178} else {179motors->set_desired_rotor_speed(0.0f);180}181break;182}183184}185186187// heli_update_autorotation - determines if aircraft is in autorotation and sets motors flag and switches188// to autorotation flight mode if manual collective is not being used.189void Copter::heli_update_autorotation()190{191bool in_autorotation_mode = false;192#if MODE_AUTOROTATE_ENABLED193in_autorotation_mode = flightmode == &mode_autorotate;194#endif195196// If we have landed then we do not want to be in autorotation and we do not want to via the bailout state197if (ap.land_complete || ap.land_complete_maybe) {198motors->force_deactivate_autorotation();199return;200}201202// if we got this far we are flying, check for conditions to set autorotation state203if (!motors->get_interlock() && (flightmode->has_manual_throttle() || in_autorotation_mode)) {204// set state in motors to facilitate manual and assisted autorotations205motors->set_autorotation_active(true);206} else {207// deactivate the autorotation state via the bailout case208motors->set_autorotation_active(false);209}210}211212// update collective low flag. Use a debounce time of 400 milliseconds.213void Copter::update_collective_low_flag(int16_t throttle_control)214{215static uint32_t last_nonzero_collective_ms = 0;216uint32_t tnow_ms = millis();217218if (throttle_control > 0) {219last_nonzero_collective_ms = tnow_ms;220heli_flags.coll_stk_low = false;221} else if (tnow_ms - last_nonzero_collective_ms > 400) {222heli_flags.coll_stk_low = true;223}224}225226#endif // FRAME_CONFIG == HELI_FRAME227228229