ardupilot/ArduCopter/Attitude.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

134 lines
4.7 KiB
C++
Raw Permalink Normal View History

#include "Copter.h"
2022-12-04 06:09:51 -04:00
/*************************************************************
* Attitude Rate controllers and timing
****************************************************************/
// update rate controllers and output to roll, pitch and yaw actuators
// called at 400hz by default
void Copter::run_rate_controller()
{
// set attitude and position controller loop time
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
motors->set_dt(last_loop_time_s);
2022-12-04 06:09:51 -04:00
attitude_control->set_dt(last_loop_time_s);
pos_control->set_dt(last_loop_time_s);
// run low level rate controllers that only require IMU data
attitude_control->rate_controller_run();
}
/*************************************************************
* throttle control
****************************************************************/
// update estimated throttle required to hover (if necessary)
// called at 100hz
void Copter::update_throttle_hover()
{
// if not armed or landed or on standby then exit
if (!motors->armed() || ap.land_complete || standby_active) {
return;
}
// do not update in manual throttle modes or Drift
if (flightmode->has_manual_throttle() || (copter.flightmode->mode_number() == Mode::Number::DRIFT)) {
return;
}
// do not update while climbing or descending
2021-05-11 01:42:02 -03:00
if (!is_zero(pos_control->get_vel_desired_cms().z)) {
return;
}
// get throttle output
float throttle = motors->get_throttle();
// calc average throttle if we are in a level hover. accounts for heli hover roll trim
2021-10-20 05:29:57 -03:00
if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z_up_cms()) < 60 &&
2022-02-26 09:50:22 -04:00
fabsf(ahrs.roll_sensor-attitude_control->get_roll_trim_cd()) < 500 && labs(ahrs.pitch_sensor) < 500) {
// Can we set the time constant automatically
motors->update_throttle_hover(0.01f);
#if HAL_GYROFFT_ENABLED
gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out());
#endif
}
}
// get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
// without any deadzone at the bottom
float Copter::get_pilot_desired_climb_rate(float throttle_control)
{
// throttle failsafe check
if (failsafe.radio || !ap.rc_receiver_present) {
return 0.0f;
}
#if TOY_MODE_ENABLED == ENABLED
if (g2.toy_mode.enabled()) {
// allow throttle to be reduced after throttle arming and for
// slower descent close to the ground
g2.toy_mode.throttle_adjust(throttle_control);
}
#endif
// ensure a reasonable throttle value
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
2014-09-02 00:38:58 -03:00
// ensure a reasonable deadzone
g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400));
2014-09-02 00:38:58 -03:00
float desired_rate = 0.0f;
const float mid_stick = get_throttle_mid();
const float deadband_top = mid_stick + g.throttle_deadzone;
const float deadband_bottom = mid_stick - g.throttle_deadzone;
// check throttle is above, below or in the deadband
if (throttle_control < deadband_bottom) {
// below the deadband
desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom;
} else if (throttle_control > deadband_top) {
// above the deadband
desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top);
} else {
// must be in the deadband
desired_rate = 0.0f;
}
return desired_rate;
}
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
float Copter::get_non_takeoff_throttle()
{
return MAX(0,motors->get_throttle_hover()/2.0f);
}
2014-02-11 09:33:08 -04:00
// set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle
void Copter::set_accel_throttle_I_from_pilot_throttle()
{
// get last throttle input sent to attitude controller
float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0f, 1.0f);
// shift difference between pilot's throttle and hover throttle into accelerometer I
pos_control->get_accel_z_pid().set_integrator((pilot_throttle-motors->get_throttle_hover()) * 1000.0f);
}
// rotate vector from vehicle's perspective to North-East frame
void Copter::rotate_body_frame_to_NE(float &x, float &y)
{
float ne_x = x*ahrs.cos_yaw() - y*ahrs.sin_yaw();
float ne_y = x*ahrs.sin_yaw() + y*ahrs.cos_yaw();
x = ne_x;
y = ne_y;
}
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
uint16_t Copter::get_pilot_speed_dn() const
{
if (g2.pilot_speed_dn == 0) {
return abs(g.pilot_speed_up);
} else {
return abs(g2.pilot_speed_dn);
}
}