2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// stabilize_init - initialise stabilize controller
|
2017-04-14 16:10:29 -03:00
|
|
|
bool Sub::stabilize_init()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// set target altitude to zero for reporting
|
2021-04-27 03:50:06 -03:00
|
|
|
pos_control.set_pos_target_z_cm(0);
|
2022-04-15 13:13:12 -03:00
|
|
|
if(prev_control_mode != control_mode_t::ALT_HOLD) {
|
|
|
|
last_roll = 0;
|
|
|
|
last_pitch = 0;
|
|
|
|
}
|
2016-08-24 19:21:29 -03:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
2015-12-30 18:57:56 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// stabilize_run - runs the main stabilize controller
|
|
|
|
// should be called at 100hz or more
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::stabilize_run()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2016-04-05 00:17:39 -03:00
|
|
|
// if not armed set throttle to zero and exit immediately
|
2017-04-11 13:45:16 -03:00
|
|
|
if (!motors.armed()) {
|
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-24 19:21:29 -03:00
|
|
|
last_pilot_heading = ahrs.yaw_sensor;
|
2022-04-13 22:10:59 -03:00
|
|
|
last_roll = 0;
|
|
|
|
last_pitch = 0;
|
2015-12-30 18:57:56 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2022-04-13 22:10:59 -03:00
|
|
|
handle_attitude();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// output pilot's throttle
|
2017-02-03 00:18:27 -04:00
|
|
|
attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
|
2016-01-08 19:25:59 -04:00
|
|
|
|
2017-02-07 19:06:36 -04:00
|
|
|
//control_in is range -1000-1000
|
2016-01-08 19:25:59 -04:00
|
|
|
//radio_in is raw pwm value
|
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
|
|
|
}
|