2017-02-03 00:18:27 -04:00
|
|
|
// ArduSub position hold flight mode
|
|
|
|
// GPS required
|
|
|
|
// Jacob Walser August 2016
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
#if POSHOLD_ENABLED == ENABLED
|
|
|
|
|
|
|
|
// poshold_init - initialise PosHold controller
|
2017-04-14 16:10:29 -03:00
|
|
|
bool Sub::poshold_init()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
// fail to initialise PosHold mode if no GPS lock
|
2017-04-14 16:10:29 -03:00
|
|
|
if (!position_ok()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-02-03 00:18:27 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// initialize vertical speeds and acceleration
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.set_max_speed_accel_xy(wp_nav.get_default_speed_xy(), wp_nav.get_wp_acceleration());
|
2021-07-08 01:16:08 -03:00
|
|
|
pos_control.set_correction_speed_accel_xy(wp_nav.get_default_speed_xy(), wp_nav.get_wp_acceleration());
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
2021-07-08 01:16:08 -03:00
|
|
|
pos_control.set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// initialise position and desired velocity
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.init_xy_controller_stopping_point();
|
2022-09-27 18:09:00 -03:00
|
|
|
// Stop all thrusters
|
|
|
|
attitude_control.set_throttle_out(0.75,true,100.0);
|
|
|
|
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.init_z_controller();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2022-09-27 18:09:00 -03:00
|
|
|
// initialise position and desired velocity
|
|
|
|
float pos = stopping_distance();
|
|
|
|
float zero = 0;
|
|
|
|
pos_control.input_pos_vel_accel_z(pos, zero, zero);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// poshold_run - runs the PosHold controller
|
|
|
|
// should be called at 100hz or more
|
2017-02-03 00:18:27 -04:00
|
|
|
void Sub::poshold_run()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2020-08-03 00:32:30 -03:00
|
|
|
// When unarmed, disable motors and stabilization
|
2017-04-13 16:34:58 -03:00
|
|
|
if (!motors.armed()) {
|
2019-04-09 20:09:55 -03:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
2020-08-03 00:32:30 -03:00
|
|
|
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
|
2022-09-27 18:09:00 -03:00
|
|
|
attitude_control.set_throttle_out(0.75f ,true, g.throttle_filt);
|
2018-12-28 02:34:55 -04:00
|
|
|
attitude_control.relax_attitude_controllers();
|
2022-09-05 18:30:37 -03:00
|
|
|
pos_control.relax_velocity_controller_xy();
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.relax_z_controller(0.5f);
|
2020-08-03 00:32:30 -03:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
2015-12-30 18:57:56 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
// set motors to full range
|
2019-04-09 20:09:55 -03:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
2017-02-03 17:33:27 -04:00
|
|
|
|
|
|
|
///////////////////////
|
|
|
|
// update xy outputs //
|
2017-03-22 17:02:00 -03:00
|
|
|
float pilot_lateral = channel_lateral->norm_input();
|
|
|
|
float pilot_forward = channel_forward->norm_input();
|
2017-02-03 17:33:27 -04:00
|
|
|
|
|
|
|
float lateral_out = 0;
|
|
|
|
float forward_out = 0;
|
|
|
|
|
2020-08-03 00:32:30 -03:00
|
|
|
if (position_ok()) {
|
|
|
|
// Allow pilot to reposition the sub
|
|
|
|
if (fabsf(pilot_lateral) > 0.1 || fabsf(pilot_forward) > 0.1) {
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.init_xy_controller_stopping_point();
|
2020-08-03 00:32:30 -03:00
|
|
|
}
|
|
|
|
translate_pos_control_rp(lateral_out, forward_out);
|
|
|
|
pos_control.update_xy_controller();
|
2017-02-03 17:33:27 -04:00
|
|
|
} else {
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.init_xy_controller_stopping_point();
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
|
|
|
/////////////////////
|
|
|
|
// Update attitude //
|
|
|
|
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
|
|
|
float target_roll, target_pitch;
|
|
|
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
|
|
|
|
|
|
|
|
// update attitude controller targets
|
|
|
|
if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input
|
2017-07-09 23:49:42 -03:00
|
|
|
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
2017-02-03 17:33:27 -04:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
|
|
|
last_pilot_yaw_input_ms = tnow; // time when pilot last changed heading
|
|
|
|
|
|
|
|
} else { // hold current heading
|
|
|
|
|
|
|
|
// this check is required to prevent bounce back after very fast yaw maneuvers
|
|
|
|
// the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped
|
|
|
|
if (tnow < last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading
|
|
|
|
target_yaw_rate = 0; // Stop rotation on yaw axis
|
|
|
|
|
|
|
|
// call attitude controller with target yaw rate = 0 to decelerate on yaw axis
|
2017-07-09 23:49:42 -03:00
|
|
|
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
2017-02-03 17:33:27 -04:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor; // update heading to hold
|
|
|
|
|
|
|
|
} else { // call attitude controller holding absolute absolute bearing
|
2017-07-09 23:49:42 -03:00
|
|
|
attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, last_pilot_heading, true);
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// Update z axis //
|
2020-08-03 00:32:30 -03:00
|
|
|
control_depth();
|
2022-05-25 13:20:51 -03:00
|
|
|
|
|
|
|
motors.set_forward(motors.get_forward() + forward_out + pilot_forward);
|
|
|
|
motors.set_lateral(motors.get_lateral() + lateral_out + pilot_lateral);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
#endif // POSHOLD_ENABLED == ENABLED
|