mirror of https://github.com/ArduPilot/ardupilot
123 lines
5.1 KiB
C++
123 lines
5.1 KiB
C++
#include "Sub.h"
|
|
|
|
|
|
bool ModeAlthold::init(bool ignore_checks) {
|
|
if(!sub.control_check_barometer()) {
|
|
return false;
|
|
}
|
|
|
|
// initialize vertical maximum speeds and acceleration
|
|
// sets the maximum speed up and down returned by position controller
|
|
position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
|
position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
|
|
|
// initialise position and desired velocity
|
|
position_control->init_z_controller();
|
|
|
|
sub.last_pilot_heading = ahrs.yaw_sensor;
|
|
|
|
return true;
|
|
}
|
|
|
|
// althold_run - runs the althold controller
|
|
// should be called at 100hz or more
|
|
void ModeAlthold::run()
|
|
{
|
|
run_pre();
|
|
control_depth();
|
|
run_post();
|
|
}
|
|
|
|
void ModeAlthold::run_pre()
|
|
{
|
|
uint32_t tnow = AP_HAL::millis();
|
|
|
|
// initialize vertical speeds and acceleration
|
|
position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
|
|
|
if (!motors.armed()) {
|
|
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
|
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
|
|
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
|
|
attitude_control->relax_attitude_controllers();
|
|
position_control->relax_z_controller(motors.get_throttle_hover());
|
|
sub.last_pilot_heading = ahrs.yaw_sensor;
|
|
return;
|
|
}
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
|
|
|
// get pilot desired lean angles
|
|
float target_roll, target_pitch;
|
|
|
|
// Check if set_attitude_target_no_gps is valid
|
|
if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
|
|
float target_yaw;
|
|
Quaternion(
|
|
sub.set_attitude_target_no_gps.packet.q
|
|
).to_euler(
|
|
target_roll,
|
|
target_pitch,
|
|
target_yaw
|
|
);
|
|
target_roll = degrees(target_roll);
|
|
target_pitch = degrees(target_pitch);
|
|
target_yaw = degrees(target_yaw);
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(target_roll * 1e2f, target_pitch * 1e2f, target_yaw * 1e2f, true);
|
|
return;
|
|
}
|
|
|
|
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->get_althold_lean_angle_max_cd());
|
|
|
|
// get pilot's desired yaw rate
|
|
float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim());
|
|
float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input);
|
|
|
|
// call attitude controller
|
|
if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
|
sub.last_pilot_heading = ahrs.yaw_sensor;
|
|
sub.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 < sub.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
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
|
sub.last_pilot_heading = ahrs.yaw_sensor; // update heading to hold
|
|
|
|
} else { // call attitude controller holding absolute bearing
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, sub.last_pilot_heading, true);
|
|
}
|
|
}
|
|
}
|
|
|
|
void ModeAlthold::run_post()
|
|
{
|
|
motors.set_forward(channel_forward->norm_input());
|
|
motors.set_lateral(channel_lateral->norm_input());
|
|
}
|
|
|
|
void ModeAlthold::control_depth() {
|
|
float target_climb_rate_cm_s = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());
|
|
target_climb_rate_cm_s = constrain_float(target_climb_rate_cm_s, -sub.get_pilot_speed_dn(), g.pilot_speed_up);
|
|
|
|
// desired_climb_rate returns 0 when within the deadzone.
|
|
//we allow full control to the pilot, but as soon as there's no input, we handle being at surface/bottom
|
|
if (fabsf(target_climb_rate_cm_s) < 0.05f) {
|
|
if (sub.ap.at_surface) {
|
|
position_control->set_pos_target_z_cm(MIN(position_control->get_pos_target_z_cm(), g.surface_depth - 5.0f)); // set target to 5 cm below surface level
|
|
} else if (sub.ap.at_bottom) {
|
|
position_control->set_pos_target_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_target_z_cm())); // set target to 10 cm above bottom
|
|
}
|
|
}
|
|
|
|
position_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cm_s);
|
|
position_control->update_z_controller();
|
|
}
|