mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_AttControl: use motor accessors to set roll, pitch, yaw, thr
Saves 8bytes of RAM
This commit is contained in:
parent
415e48de19
commit
f216cffb77
@ -239,9 +239,9 @@ void AC_AttitudeControl::rate_controller_run()
|
||||
// call rate controllers and send output to motors object
|
||||
// To-Do: should the outputs from get_rate_roll, pitch, yaw be int16_t which is the input to the motors library?
|
||||
// To-Do: skip this step if the throttle out is zero?
|
||||
_motor_roll = rate_bf_to_motor_roll(_rate_bf_target.x);
|
||||
_motor_pitch = rate_bf_to_motor_pitch(_rate_bf_target.y);
|
||||
_motor_yaw = rate_bf_to_motor_yaw(_rate_bf_target.z);
|
||||
_motors.set_roll(rate_bf_to_motor_roll(_rate_bf_target.x));
|
||||
_motors.set_pitch(rate_bf_to_motor_pitch(_rate_bf_target.y));
|
||||
_motors.set_yaw(rate_bf_to_motor_yaw(_rate_bf_target.z));
|
||||
}
|
||||
|
||||
//
|
||||
@ -438,9 +438,9 @@ float AC_AttitudeControl::rate_bf_to_motor_yaw(float rate_target_cds)
|
||||
void AC_AttitudeControl::set_throttle_out(int16_t throttle_out, bool apply_angle_boost)
|
||||
{
|
||||
if (apply_angle_boost) {
|
||||
_motor_throttle = get_angle_boost(throttle_out);
|
||||
_motors.set_throttle(get_angle_boost(throttle_out));
|
||||
}else{
|
||||
_motor_throttle = throttle_out;
|
||||
_motors.set_throttle(throttle_out);
|
||||
// clear angle_boost for logging purposes
|
||||
_angle_boost = 0;
|
||||
}
|
||||
|
@ -41,8 +41,7 @@ public:
|
||||
const AP_Vehicle::MultiCopter &aparm,
|
||||
AP_Motors& motors,
|
||||
APM_PI& pi_angle_roll, APM_PI& pi_angle_pitch, APM_PI& pi_angle_yaw,
|
||||
AC_PID& pid_rate_roll, AC_PID& pid_rate_pitch, AC_PID& pid_rate_yaw,
|
||||
int16_t& motor_roll, int16_t& motor_pitch, int16_t& motor_yaw, int16_t& motor_throttle
|
||||
AC_PID& pid_rate_roll, AC_PID& pid_rate_pitch, AC_PID& pid_rate_yaw
|
||||
) :
|
||||
_ahrs(ahrs),
|
||||
_ins(ins),
|
||||
@ -54,10 +53,6 @@ public:
|
||||
_pid_rate_roll(pid_rate_roll),
|
||||
_pid_rate_pitch(pid_rate_pitch),
|
||||
_pid_rate_yaw(pid_rate_yaw),
|
||||
_motor_roll(motor_roll),
|
||||
_motor_pitch(motor_pitch),
|
||||
_motor_yaw(motor_yaw),
|
||||
_motor_throttle(motor_throttle),
|
||||
_dt(AC_ATTITUDE_100HZ_DT),
|
||||
_angle_boost(0)
|
||||
{
|
||||
@ -207,10 +202,6 @@ protected:
|
||||
AC_PID& _pid_rate_roll;
|
||||
AC_PID& _pid_rate_pitch;
|
||||
AC_PID& _pid_rate_yaw;
|
||||
int16_t& _motor_roll; // g.rc_1.servo_out
|
||||
int16_t& _motor_pitch; // g.rc_2.servo_out
|
||||
int16_t& _motor_yaw; // g.rc_4.servo_out
|
||||
int16_t& _motor_throttle; // g.rc_3.servo_out
|
||||
|
||||
// parameters
|
||||
AP_Float _angle_rate_rp_max; // maximum rate request output from the earth-frame angle controller for roll and pitch axis
|
||||
|
Loading…
Reference in New Issue
Block a user