ardupilot/ArduSub/control_stabilize.cpp

41 lines
1.2 KiB
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
// stabilize_init - initialise stabilize controller
bool Sub::stabilize_init()
{
// set target altitude to zero for reporting
2021-04-27 03:50:06 -03:00
pos_control.set_pos_target_z_cm(0);
if(prev_control_mode != control_mode_t::ALT_HOLD) {
last_roll = 0;
last_pitch = 0;
}
last_pilot_heading = ahrs.yaw_sensor;
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()
{
2016-04-05 00:17:39 -03:00
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control.set_throttle_out(0,true,g.throttle_filt);
attitude_control.relax_attitude_controllers();
last_pilot_heading = ahrs.yaw_sensor;
2022-04-13 22:10:59 -03:00
last_roll = 0;
last_pitch = 0;
return;
}
2022-04-13 22:10:59 -03:00
handle_attitude();
// output pilot's throttle
attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
2017-02-07 19:06:36 -04:00
//control_in is range -1000-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}