ardupilot/ArduSub/mode_stabilize.cpp

70 lines
2.9 KiB
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
2023-04-03 09:11:21 -03:00
bool ModeStabilize::init(bool ignore_checks) {
// set target altitude to zero for reporting
2023-04-03 09:11:21 -03:00
position_control->set_pos_target_z_cm(0);
sub.last_pilot_heading = ahrs.yaw_sensor;
return true;
2023-04-03 09:11:21 -03:00
return true;
}
2023-04-03 09:11:21 -03:00
void ModeStabilize::run()
{
2023-04-03 09:11:21 -03:00
uint32_t tnow = AP_HAL::millis();
float target_roll, target_pitch;
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);
2023-04-03 09:11:21 -03:00
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.last_pilot_heading = ahrs.yaw_sensor;
return;
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
2016-04-05 00:17:39 -03:00
// convert pilot input to lean angles
2023-04-03 09:11:21 -03:00
// To-Do: convert sub.get_pilot_desired_lean_angles to return angles as floats
// TODO2: move into mode.h
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);
// 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
// update attitude controller targets
if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input
2023-04-03 09:11:21 -03:00
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
2023-04-03 09:11:21 -03:00
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
2023-04-03 09:11:21 -03:00
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 absolute bearing
2023-04-03 09:11:21 -03:00
attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, sub.last_pilot_heading, true);
}
}
// output pilot's throttle
2023-04-03 09:11:21 -03:00
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());
}