2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
* control_althold.pde - init and run calls for althold, flight mode
|
|
|
|
*/
|
|
|
|
|
|
|
|
// althold_init - initialise althold controller
|
2017-04-14 16:10:29 -03:00
|
|
|
bool Sub::althold_init()
|
2015-12-30 18:57:56 -04: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-24 18:50:20 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// initialize vertical speeds and leash lengths
|
2016-01-20 23:29:51 -04:00
|
|
|
// sets the maximum speed up and down returned by position controller
|
2018-09-20 02:44:52 -03:00
|
|
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
|
|
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
2015-12-30 18:57:56 -04: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());
|
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// althold_run - runs the althold controller
|
|
|
|
// should be called at 100hz or more
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::althold_run()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// initialize vertical speeds and acceleration
|
2018-09-20 02:44:52 -03:00
|
|
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
|
|
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-04-11 13:45:16 -03:00
|
|
|
if (!motors.armed()) {
|
2017-02-03 00:18:27 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
2017-02-10 13:46:54 -04:00
|
|
|
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
|
2017-02-03 00:18:27 -04:00
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
|
|
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2017-02-03 00:18:27 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// get pilot desired lean angles
|
|
|
|
float target_roll, target_pitch;
|
2018-04-14 00:15:15 -03:00
|
|
|
|
|
|
|
// 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(
|
|
|
|
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;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-06-28 12:18:49 -03:00
|
|
|
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());
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// get pilot's desired yaw rate
|
2017-02-03 00:18:27 -04:00
|
|
|
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
// call attitude controller
|
|
|
|
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
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-02-27 14:06:55 -04:00
|
|
|
if (fabsf(channel_throttle->norm_input()-0.5) > 0.05) { // Throttle input above 5%
|
|
|
|
// output pilot's throttle
|
|
|
|
attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
|
|
|
|
// reset z targets to current values
|
|
|
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
|
|
|
} else { // hold z
|
|
|
|
|
|
|
|
if (ap.at_bottom) {
|
|
|
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); // clear velocity and position targets, and integrator
|
|
|
|
pos_control.set_alt_target(inertial_nav.get_altitude() + 10.0f); // set target to 10 cm above bottom
|
|
|
|
} else if (rangefinder_alt_ok()) {
|
|
|
|
// if rangefinder is ok, use surface tracking
|
|
|
|
float target_climb_rate = get_surface_tracking_climb_rate(0, pos_control.get_alt_target(), G_Dt);
|
|
|
|
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
|
|
|
}
|
|
|
|
pos_control.update_z_controller();
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
motors.set_forward(channel_forward->norm_input());
|
|
|
|
motors.set_lateral(channel_lateral->norm_input());
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|