2016-08-25 00:08:30 -03:00
|
|
|
#include "Sub.h"
|
|
|
|
|
|
|
|
|
2017-04-14 16:10:29 -03:00
|
|
|
bool Sub::surface_init()
|
2016-08-25 00:08:30 -03:00
|
|
|
{
|
2018-04-14 00:16:57 -03:00
|
|
|
if(!control_check_barometer()) {
|
2017-02-03 17:33:27 -04:00
|
|
|
return false;
|
|
|
|
}
|
2016-08-25 00:08:30 -03:00
|
|
|
|
|
|
|
// initialize vertical speeds and leash lengths
|
2019-01-24 01:04:22 -04:00
|
|
|
pos_control.set_max_speed_z(wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
|
2018-09-20 02:44:52 -03:00
|
|
|
pos_control.set_max_accel_z(wp_nav.get_accel_z());
|
2016-08-25 00:08:30 -03:00
|
|
|
|
|
|
|
// initialise position and desired velocity
|
|
|
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
|
|
|
pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
|
|
|
|
|
|
|
|
return true;
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
void Sub::surface_run()
|
|
|
|
{
|
|
|
|
float target_roll, target_pitch;
|
|
|
|
float target_yaw_rate;
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
2017-04-11 13:45:16 -03:00
|
|
|
if (!motors.armed()) {
|
2017-02-03 17:33:27 -04:00
|
|
|
motors.output_min();
|
2019-04-09 20:09:55 -03:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
2018-12-28 02:34:55 -04:00
|
|
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
|
|
|
attitude_control.relax_attitude_controllers();
|
2016-08-25 00:08:30 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Already at surface, hold depth at surface
|
2017-02-03 17:33:27 -04:00
|
|
|
if (ap.at_surface) {
|
2019-10-17 00:50:07 -03:00
|
|
|
set_mode(ALT_HOLD, ModeReason::SURFACE_COMPLETE);
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
2016-08-25 00:08:30 -03:00
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
|
|
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
|
|
|
|
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
|
|
|
|
|
|
|
// call attitude controller
|
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);
|
2016-08-25 00:08:30 -03:00
|
|
|
|
|
|
|
// set target climb rate
|
2019-09-17 06:50:00 -03:00
|
|
|
float cmb_rate = constrain_float(fabsf(wp_nav.get_default_speed_up()), 1, pos_control.get_max_speed_up());
|
2016-08-25 00:08:30 -03:00
|
|
|
|
|
|
|
// record desired climb rate for logging
|
|
|
|
desired_climb_rate = cmb_rate;
|
|
|
|
|
|
|
|
// update altitude target and call position controller
|
|
|
|
pos_control.set_alt_target_from_climb_rate_ff(cmb_rate, G_Dt, true);
|
|
|
|
pos_control.update_z_controller();
|
|
|
|
|
|
|
|
// pilot has control for repositioning
|
2016-11-17 16:00:47 -04:00
|
|
|
motors.set_forward(channel_forward->norm_input());
|
|
|
|
motors.set_lateral(channel_lateral->norm_input());
|
2016-08-25 00:08:30 -03:00
|
|
|
}
|