ardupilot/ArduSub/control_circle.cpp

95 lines
3.2 KiB
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
/*
* control_circle.pde - init and run calls for circle flight mode
*/
// circle_init - initialise circle controller flight mode
bool Sub::circle_init()
{
if (!position_ok()) {
return false;
}
2017-03-04 20:46:00 -04:00
circle_pilot_yaw_override = false;
2017-03-04 20:46:00 -04:00
// initialize speeds and accelerations
pos_control.set_speed_xy(wp_nav.get_speed_xy());
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
pos_control.set_jerk_xy_to_default();
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
pos_control.set_accel_z(g.pilot_accel_z);
2017-03-04 20:46:00 -04:00
// initialise circle controller including setting the circle center based on vehicle speed
circle_nav.init();
return true;
}
// circle_run - runs the circle flight mode
// should be called at 100hz or more
2016-01-14 15:30:56 -04:00
void Sub::circle_run()
{
float target_yaw_rate = 0;
float target_climb_rate = 0;
2017-03-04 20:46:00 -04:00
// update parameters, to allow changing at runtime
pos_control.set_speed_xy(wp_nav.get_speed_xy());
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
pos_control.set_accel_z(g.pilot_accel_z);
2017-04-13 16:34:58 -03:00
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
// To-Do: add some initialisation of position controllers
2016-04-05 00:17:39 -03: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 disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
2016-02-23 02:15:15 -04:00
pos_control.set_alt_target_to_current_alt();
return;
}
// process pilot inputs
2017-03-04 20:46:00 -04:00
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
circle_pilot_yaw_override = true;
}
2017-03-04 20:46:00 -04:00
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
2016-04-05 00:17:39 -03:00
// set motors to full range
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run circle controller
circle_nav.update();
2017-03-04 20:46:00 -04:00
///////////////////////
// update xy outputs //
float lateral_out, forward_out;
translate_circle_nav_rp(lateral_out, forward_out);
// Send to forward/lateral outputs
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
// call attitude controller
if (circle_pilot_yaw_override) {
2017-03-04 20:46:00 -04:00
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate, get_smoothing_gain());
} else {
2017-03-04 20:46:00 -04:00
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true, get_smoothing_gain());
}
// adjust climb rate using rangefinder
if (rangefinder_alt_ok()) {
// if rangefinder is ok, use surface tracking
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
}
// update altitude target and call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
pos_control.update_z_controller();
}