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_poshold.cpp
Views: 1798
// ArduSub position hold flight mode1// GPS required2// Jacob Walser August 201634#include "Sub.h"56#if POSHOLD_ENABLED78// poshold_init - initialise PosHold controller9bool ModePoshold::init(bool ignore_checks)10{11// fail to initialise PosHold mode if no GPS lock12if (!sub.position_ok()) {13return false;14}1516// initialize vertical speeds and acceleration17position_control->set_max_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration());18position_control->set_correction_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration());19position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);20position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);2122// initialise position and desired velocity23position_control->init_xy_controller_stopping_point();24position_control->init_z_controller();2526// Stop all thrusters27attitude_control->set_throttle_out(0.5f ,true, g.throttle_filt);28attitude_control->relax_attitude_controllers();29position_control->relax_z_controller(0.5f);3031sub.last_pilot_heading = ahrs.yaw_sensor;3233return true;34}3536// poshold_run - runs the PosHold controller37// should be called at 100hz or more38void ModePoshold::run()39{40uint32_t tnow = AP_HAL::millis();41// When unarmed, disable motors and stabilization42if (!motors.armed()) {43motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);44// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)45attitude_control->set_throttle_out(0.5f ,true, g.throttle_filt);46attitude_control->relax_attitude_controllers();47position_control->init_xy_controller_stopping_point();48position_control->relax_z_controller(0.5f);49sub.last_pilot_heading = ahrs.yaw_sensor;50return;51}5253// set motors to full range54motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);5556///////////////////////57// update xy outputs //58float pilot_lateral = channel_lateral->norm_input();59float pilot_forward = channel_forward->norm_input();6061float lateral_out = 0;62float forward_out = 0;6364if (sub.position_ok()) {65// Allow pilot to reposition the sub66if (fabsf(pilot_lateral) > 0.1 || fabsf(pilot_forward) > 0.1) {67position_control->init_xy_controller_stopping_point();68}69sub.translate_pos_control_rp(lateral_out, forward_out);70position_control->update_xy_controller();71} else {72position_control->init_xy_controller_stopping_point();73}74motors.set_forward(forward_out + pilot_forward);75motors.set_lateral(lateral_out + pilot_lateral);76/////////////////////77// Update attitude //7879// get pilot's desired yaw rate80float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim());81float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input);8283// convert pilot input to lean angles84// To-Do: convert get_pilot_desired_lean_angles to return angles as floats85float target_roll, target_pitch;86sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);8788// update attitude controller targets89if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input90attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);91sub.last_pilot_heading = ahrs.yaw_sensor;92sub.last_pilot_yaw_input_ms = tnow; // time when pilot last changed heading9394} else { // hold current heading9596// this check is required to prevent bounce back after very fast yaw manoeuvres97// the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped98if (tnow < sub.last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading99target_yaw_rate = 0; // Stop rotation on yaw axis100101// call attitude controller with target yaw rate = 0 to decelerate on yaw axis102attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);103sub.last_pilot_heading = ahrs.yaw_sensor; // update heading to hold104105} else { // call attitude controller holding absolute absolute bearing106attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, sub.last_pilot_heading, true);107}108}109110// Update z axis //111control_depth();112}113#endif // POSHOLD_ENABLED114115116