123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281 |
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Math/AP_Math.h>
- #include "AP_MotorsSingle.h"
- #include <GCS_MAVLink/GCS.h>
- extern const AP_HAL::HAL& hal;
- void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame_type)
- {
-
- for (uint8_t i = 0; i < 6; i++) {
- add_motor_num(CH_1 + i);
- }
-
- motor_enabled[AP_MOTORS_MOT_5] = true;
- motor_enabled[AP_MOTORS_MOT_6] = true;
-
- for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
- SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- }
-
- _flags.initialised_ok = (frame_class == MOTOR_FRAME_SINGLE);
- }
- void AP_MotorsSingle::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
- {
-
- }
- void AP_MotorsSingle::set_update_rate(uint16_t speed_hz)
- {
-
- _speed_hz = speed_hz;
- uint32_t mask =
- 1U << AP_MOTORS_MOT_5 |
- 1U << AP_MOTORS_MOT_6 ;
- rc_set_freq(mask, _speed_hz);
- }
- void AP_MotorsSingle::output_to_motors()
- {
- if (!_flags.initialised_ok) {
- return;
- }
- switch (_spool_state) {
- case SpoolState::SHUT_DOWN:
-
- rc_write_angle(AP_MOTORS_MOT_1, _roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- rc_write_angle(AP_MOTORS_MOT_2, _pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- rc_write_angle(AP_MOTORS_MOT_3, -_roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- rc_write_angle(AP_MOTORS_MOT_4, -_pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- rc_write(AP_MOTORS_MOT_5, output_to_pwm(0));
- rc_write(AP_MOTORS_MOT_6, output_to_pwm(0));
- break;
- case SpoolState::GROUND_IDLE:
-
- for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
- rc_write_angle(AP_MOTORS_MOT_1 + i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- }
- set_actuator_with_slew(_actuator[5], actuator_spin_up_to_ground_idle());
- set_actuator_with_slew(_actuator[6], actuator_spin_up_to_ground_idle());
- rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
- rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
- break;
- case SpoolState::SPOOLING_UP:
- case SpoolState::THROTTLE_UNLIMITED:
- case SpoolState::SPOOLING_DOWN:
-
- for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
- rc_write_angle(AP_MOTORS_MOT_1 + i, _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
- }
- set_actuator_with_slew(_actuator[5], thrust_to_actuator(_thrust_out));
- set_actuator_with_slew(_actuator[6], thrust_to_actuator(_thrust_out));
- rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
- rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
- break;
- }
- }
- uint16_t AP_MotorsSingle::get_motor_mask()
- {
- uint32_t motor_mask =
- 1U << AP_MOTORS_MOT_1 |
- 1U << AP_MOTORS_MOT_2 |
- 1U << AP_MOTORS_MOT_3 |
- 1U << AP_MOTORS_MOT_4 |
- 1U << AP_MOTORS_MOT_5 |
- 1U << AP_MOTORS_MOT_6;
- uint16_t mask = rc_map_mask(motor_mask);
-
- mask |= AP_MotorsMulticopter::get_motor_mask();
- return mask;
- }
- void AP_MotorsSingle::output_armed_stabilizing()
- {
- float roll_thrust;
- float pitch_thrust;
- float yaw_thrust;
- float throttle_thrust;
- float throttle_avg_max;
- float thrust_min_rpy;
- float thr_adj;
- float rp_scale = 1.0f;
- float actuator_allowed = 0.0f;
- float actuator[NUM_ACTUATORS];
- float actuator_max = 0.0f;
-
- const float compensation_gain = get_compensation_gain();
- roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
- pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
- yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
- throttle_thrust = get_throttle() * compensation_gain;
- throttle_avg_max = _throttle_avg_max * compensation_gain;
-
- if (throttle_thrust <= 0.0f) {
- throttle_thrust = 0.0f;
- limit.throttle_lower = true;
- }
- if (throttle_thrust >= _throttle_thrust_max) {
- throttle_thrust = _throttle_thrust_max;
- limit.throttle_upper = true;
- }
- throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
- float rp_thrust_max = MAX(fabsf(roll_thrust), fabsf(pitch_thrust));
-
- if (is_zero(rp_thrust_max)) {
- rp_scale = 1.0f;
- } else {
- rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float) _yaw_headroom / 1000.0f)) / rp_thrust_max, 0.0f, 1.0f);
- if (rp_scale < 1.0f) {
- limit.roll = true;
- limit.pitch = true;
- }
- }
- actuator_allowed = 1.0f - rp_scale * rp_thrust_max;
- if (fabsf(yaw_thrust) > actuator_allowed) {
- yaw_thrust = constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed);
- limit.yaw = true;
- }
-
-
- actuator[0] = rp_scale * roll_thrust - yaw_thrust;
-
- actuator[1] = rp_scale * pitch_thrust - yaw_thrust;
-
- actuator[2] = -rp_scale * roll_thrust - yaw_thrust;
-
- actuator[3] = -rp_scale * pitch_thrust - yaw_thrust;
-
- thrust_min_rpy = MAX(MAX(fabsf(actuator[0]), fabsf(actuator[1])), MAX(fabsf(actuator[2]), fabsf(actuator[3])));
- thr_adj = throttle_thrust - throttle_avg_max;
- if (thr_adj < (thrust_min_rpy - throttle_avg_max)) {
-
-
- thr_adj = MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max;
- }
-
- _thrust_out = throttle_avg_max + thr_adj;
- if (is_zero(_thrust_out)) {
- limit.roll = true;
- limit.pitch = true;
- limit.yaw = true;
- }
-
- float thrust_out_actuator = constrain_float(MAX(_throttle_hover * 0.5f, _thrust_out), 0.5f, 1.0f);
-
- for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
- if (actuator_max > fabsf(actuator[i])) {
- actuator_max = fabsf(actuator[i]);
- }
- }
- if (actuator_max > thrust_out_actuator && !is_zero(actuator_max)) {
-
-
- limit.roll = true;
- limit.pitch = true;
- limit.yaw = true;
- rp_scale = thrust_out_actuator / actuator_max;
- } else {
- rp_scale = 1.0f;
- }
-
-
-
-
- for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
- _actuator_out[i] = constrain_float(rp_scale * actuator[i] / thrust_out_actuator, -1.0f, 1.0f);
- }
- }
- void AP_MotorsSingle::output_test_seq(uint8_t motor_seq, int16_t pwm)
- {
-
- if (!armed()) {
- return;
- }
-
- switch (motor_seq) {
- case 1:
-
- rc_write(AP_MOTORS_MOT_1, pwm);
- break;
- case 2:
-
- rc_write(AP_MOTORS_MOT_2, pwm);
- break;
- case 3:
-
- rc_write(AP_MOTORS_MOT_3, pwm);
- break;
- case 4:
-
- rc_write(AP_MOTORS_MOT_4, pwm);
- break;
- case 5:
-
- rc_write(AP_MOTORS_MOT_5, pwm);
- break;
- case 6:
-
- rc_write(AP_MOTORS_MOT_6, pwm);
- break;
- default:
-
- break;
- }
- }
|