#pragma once
#include <AP_Notify/AP_Notify.h>
extern const AP_HAL::HAL& hal;
#define NUM_FINS 4
#define RC_SCALE 1000
class Fins
{
public:
friend class Blimp;
friend class Loiter;
enum motor_frame_class {
MOTOR_FRAME_UNDEFINED = 0,
MOTOR_FRAME_AIRFISH = 1,
};
enum motor_frame_type {
MOTOR_FRAME_TYPE_AIRFISH = 1,
};
Fins(uint16_t loop_rate);
static const struct AP_Param::GroupInfo var_info[];
bool initialised_ok() const
{
return true;
}
void armed(bool arm)
{
if (arm != _armed) {
_armed = arm;
AP_Notify::flags.armed = arm;
}
}
bool armed() const
{
return _armed;
}
protected:
const uint16_t _loop_rate;
uint16_t _speed_hz;
float _throttle_avg_max;
float _time;
bool _armed;
float _amp[NUM_FINS];
float _off[NUM_FINS];
float _freq[NUM_FINS];
float _pos[NUM_FINS];
float _right_amp_factor[NUM_FINS];
float _front_amp_factor[NUM_FINS];
float _down_amp_factor[NUM_FINS];
float _yaw_amp_factor[NUM_FINS];
float _right_off_factor[NUM_FINS];
float _front_off_factor[NUM_FINS];
float _down_off_factor[NUM_FINS];
float _yaw_off_factor[NUM_FINS];
int8_t _num_added;
public:
float right_out;
float front_out;
float yaw_out;
float down_out;
AP_Float freq_hz;
AP_Int8 turbo_mode;
bool _interlock;
bool _initialised_ok;
void output_min();
void add_fin(int8_t fin_num, float right_amp_fac, float front_amp_fac, float yaw_amp_fac, float down_amp_fac,
float right_off_fac, float front_off_fac, float yaw_off_fac, float down_off_fac);
void setup_fins();
void output();
float get_throttle()
{
return fmaxf(fmaxf(fabsf(down_out),fabsf(front_out)), fmaxf(fabsf(right_out),fabsf(yaw_out)));
}
void rc_write(uint8_t chan, uint16_t pwm);
};