mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-06 02:25:59 +08:00
Sub: Refactor "Copter" to "Sub".
This commit is contained in:
committed by
Andrew Tridgell
parent
aaf9bec83a
commit
83ff3931b8
@@ -1,17 +1,17 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Copter.h"
|
||||
#include "Sub.h"
|
||||
|
||||
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth
|
||||
// result is a number from 2 to 12 with 2 being very sluggish and 12 being very crisp
|
||||
float Copter::get_smoothing_gain()
|
||||
float Sub::get_smoothing_gain()
|
||||
{
|
||||
return (2.0f + (float)g.rc_feel_rp/10.0f);
|
||||
}
|
||||
|
||||
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
|
||||
// returns desired angle in centi-degrees
|
||||
void Copter::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max)
|
||||
void Sub::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max)
|
||||
{
|
||||
// sanity check angle max parameter
|
||||
aparm.angle_max = constrain_int16(aparm.angle_max,1000,8000);
|
||||
@@ -43,14 +43,14 @@ void Copter::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float
|
||||
// get_pilot_desired_heading - transform pilot's yaw input into a
|
||||
// desired yaw rate
|
||||
// returns desired yaw rate in centi-degrees per second
|
||||
float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
|
||||
float Sub::get_pilot_desired_yaw_rate(int16_t stick_angle)
|
||||
{
|
||||
// convert pilot input to the desired yaw rate
|
||||
return stick_angle * g.acro_yaw_p;
|
||||
}
|
||||
|
||||
// check for ekf yaw reset and adjust target heading
|
||||
void Copter::check_ekf_yaw_reset()
|
||||
void Sub::check_ekf_yaw_reset()
|
||||
{
|
||||
float yaw_angle_change_rad = 0.0f;
|
||||
uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);
|
||||
@@ -66,7 +66,7 @@ void Copter::check_ekf_yaw_reset()
|
||||
|
||||
// get_roi_yaw - returns heading towards location held in roi_WP
|
||||
// should be called at 100hz
|
||||
float Copter::get_roi_yaw()
|
||||
float Sub::get_roi_yaw()
|
||||
{
|
||||
static uint8_t roi_yaw_counter = 0; // used to reduce update rate to 100hz
|
||||
|
||||
@@ -79,7 +79,7 @@ float Copter::get_roi_yaw()
|
||||
return yaw_look_at_WP_bearing;
|
||||
}
|
||||
|
||||
float Copter::get_look_ahead_yaw()
|
||||
float Sub::get_look_ahead_yaw()
|
||||
{
|
||||
const Vector3f& vel = inertial_nav.get_velocity();
|
||||
float speed = pythagorous2(vel.x,vel.y);
|
||||
@@ -96,7 +96,7 @@ float Copter::get_look_ahead_yaw()
|
||||
|
||||
// update_thr_average - update estimated throttle required to hover (if necessary)
|
||||
// should be called at 100hz
|
||||
void Copter::update_thr_average()
|
||||
void Sub::update_thr_average()
|
||||
{
|
||||
// ensure throttle_average has been initialised
|
||||
if( is_zero(throttle_average) ) {
|
||||
@@ -122,7 +122,7 @@ void Copter::update_thr_average()
|
||||
}
|
||||
|
||||
// set_throttle_takeoff - allows parents to tell throttle controller we are taking off so I terms can be cleared
|
||||
void Copter::set_throttle_takeoff()
|
||||
void Sub::set_throttle_takeoff()
|
||||
{
|
||||
// tell position controller to reset alt target and reset I terms
|
||||
pos_control.init_takeoff();
|
||||
@@ -134,7 +134,7 @@ void Copter::set_throttle_takeoff()
|
||||
// get_pilot_desired_throttle - transform pilot's throttle input to make cruise throttle mid stick
|
||||
// used only for manual throttle modes
|
||||
// returns throttle output 0 to 1000
|
||||
int16_t Copter::get_pilot_desired_throttle(int16_t throttle_control)
|
||||
int16_t Sub::get_pilot_desired_throttle(int16_t throttle_control)
|
||||
{
|
||||
int16_t throttle_out;
|
||||
|
||||
@@ -162,7 +162,7 @@ int16_t Copter::get_pilot_desired_throttle(int16_t throttle_control)
|
||||
// get_pilot_desired_climb_rate - transform pilot's throttle input to
|
||||
// climb rate in cm/s. we use radio_in instead of control_in to get the full range
|
||||
// without any deadzone at the bottom
|
||||
float Copter::get_pilot_desired_climb_rate(float throttle_control)
|
||||
float Sub::get_pilot_desired_climb_rate(float throttle_control)
|
||||
{
|
||||
// throttle failsafe check
|
||||
if( failsafe.radio ) {
|
||||
@@ -199,12 +199,12 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
|
||||
}
|
||||
|
||||
// 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()
|
||||
float Sub::get_non_takeoff_throttle()
|
||||
{
|
||||
return (g.throttle_mid / 2.0f);
|
||||
}
|
||||
|
||||
float Copter::get_takeoff_trigger_throttle()
|
||||
float Sub::get_takeoff_trigger_throttle()
|
||||
{
|
||||
return channel_throttle->get_control_mid() + g.takeoff_trigger_dz;
|
||||
}
|
||||
@@ -212,7 +212,7 @@ float Copter::get_takeoff_trigger_throttle()
|
||||
// get_throttle_pre_takeoff - convert pilot's input throttle to a throttle output before take-off
|
||||
// used only for althold, loiter, hybrid flight modes
|
||||
// returns throttle output 0 to 1000
|
||||
float Copter::get_throttle_pre_takeoff(float input_thr)
|
||||
float Sub::get_throttle_pre_takeoff(float input_thr)
|
||||
{
|
||||
// exit immediately if input_thr is zero
|
||||
if (input_thr <= 0.0f) {
|
||||
@@ -251,7 +251,7 @@ float Copter::get_throttle_pre_takeoff(float input_thr)
|
||||
|
||||
// get_surface_tracking_climb_rate - hold copter at the desired distance above the ground
|
||||
// returns climb rate (in cm/s) which should be passed to the position controller
|
||||
float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
|
||||
float Sub::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
|
||||
{
|
||||
static uint32_t last_call_ms = 0;
|
||||
float distance_error;
|
||||
@@ -285,14 +285,14 @@ float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current
|
||||
}
|
||||
|
||||
// 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(int16_t pilot_throttle)
|
||||
void Sub::set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle)
|
||||
{
|
||||
// shift difference between pilot's throttle and hover throttle into accelerometer I
|
||||
g.pid_accel_z.set_integrator(pilot_throttle-throttle_average);
|
||||
}
|
||||
|
||||
// updates position controller's maximum altitude using fence and EKF limits
|
||||
void Copter::update_poscon_alt_max()
|
||||
void Sub::update_poscon_alt_max()
|
||||
{
|
||||
float alt_limit_cm = 0.0f; // interpreted as no limit if left as zero
|
||||
|
||||
@@ -316,7 +316,7 @@ void Copter::update_poscon_alt_max()
|
||||
}
|
||||
|
||||
// rotate vector from vehicle's perspective to North-East frame
|
||||
void Copter::rotate_body_frame_to_NE(float &x, float &y)
|
||||
void Sub::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();
|
||||
|
||||
Reference in New Issue
Block a user