Browse Source

AC_AttControlHeli: use motor accessors to set roll, pitch, yaw, thr

mission-4.1.18
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
8baf5ebf4a
  1. 10
      libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
  2. 9
      libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h

10
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp

@ -71,8 +71,8 @@ void AC_AttitudeControl_Heli::rate_controller_run()
// call rate controllers and send output to motors object // 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: 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? // To-Do: skip this step if the throttle out is zero?
rate_bf_to_motor_roll_pitch(_rate_bf_target.x, _rate_bf_target.y, _motor_roll, _motor_pitch); rate_bf_to_motor_roll_pitch(_rate_bf_target.x, _rate_bf_target.y);
_motor_yaw = rate_bf_to_motor_yaw(_rate_bf_target.z); _motors.set_yaw(rate_bf_to_motor_yaw(_rate_bf_target.z));
} }
// //
@ -84,7 +84,7 @@ void AC_AttitudeControl_Heli::rate_controller_run()
// //
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target_cds, float rate_pitch_target_cds, int16_t& motor_roll, int16_t& motor_pitch) void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target_cds, float rate_pitch_target_cds)
{ {
float roll_pd, roll_i; // used to capture pid values float roll_pd, roll_i; // used to capture pid values
float pitch_pd, pitch_i; // used to capture pid values float pitch_pd, pitch_i; // used to capture pid values
@ -155,8 +155,8 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target
} }
// output to motors // output to motors
motor_roll = roll_out; _motors.set_roll(roll_out);
motor_pitch = pitch_out; _motors.set_pitch(pitch_out);
/* /*
#if HELI_CC_COMP == ENABLED #if HELI_CC_COMP == ENABLED

9
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h

@ -20,13 +20,11 @@ public:
const AP_Vehicle::MultiCopter &aparm, const AP_Vehicle::MultiCopter &aparm,
AP_MotorsHeli& motors, AP_MotorsHeli& motors,
APM_PI& pi_angle_roll, APM_PI& pi_angle_pitch, APM_PI& pi_angle_yaw, 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, 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_AttitudeControl(ahrs, ins, aparm, motors, AC_AttitudeControl(ahrs, ins, aparm, motors,
pi_angle_roll, pi_angle_pitch, pi_angle_yaw, pi_angle_roll, pi_angle_pitch, pi_angle_yaw,
pid_rate_roll, pid_rate_pitch, pid_rate_yaw, pid_rate_roll, pid_rate_pitch, pid_rate_yaw)
motor_roll, motor_pitch, motor_yaw, motor_throttle)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }
@ -55,7 +53,8 @@ private:
// body-frame rate controller // body-frame rate controller
// //
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in centi-degrees/sec) for roll, pitch and yaw // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in centi-degrees/sec) for roll, pitch and yaw
void rate_bf_to_motor_roll_pitch(float rate_roll_target_cds, float rate_pitch_target_cds, int16_t& motor_roll, int16_t& motor_pitch); // outputs are sent directly to motor class
void rate_bf_to_motor_roll_pitch(float rate_roll_target_cds, float rate_pitch_target_cds);
virtual float rate_bf_to_motor_yaw(float rate_yaw_cds); virtual float rate_bf_to_motor_yaw(float rate_yaw_cds);
// //

Loading…
Cancel
Save