Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Blimp/Fins.h
Views: 1798
//This class converts horizontal acceleration commands to fin flapping commands.1#pragma once2#include <AP_Notify/AP_Notify.h>34extern const AP_HAL::HAL& hal;56#define NUM_FINS 4 //Current maximum number of fins that can be added.7#define RC_SCALE 10008class Fins9{10public:11friend class Blimp;12friend class Loiter;1314enum motor_frame_class {15MOTOR_FRAME_UNDEFINED = 0,16MOTOR_FRAME_AIRFISH = 1,17};18enum motor_frame_type {19MOTOR_FRAME_TYPE_AIRFISH = 1,20};2122//constructor23Fins(uint16_t loop_rate);2425// var_info for holding Parameter information26static const struct AP_Param::GroupInfo var_info[];2728bool initialised_ok() const29{30return true;31}3233void armed(bool arm)34{35if (arm != _armed) {36_armed = arm;37AP_Notify::flags.armed = arm;38}3940}41bool armed() const42{43return _armed;44}4546protected:47// internal variables48const uint16_t _loop_rate; // rate in Hz at which output() function is called (normally 400hz)49uint16_t _speed_hz; // speed in hz to send updates to motors50float _throttle_avg_max; // last throttle input from set_throttle_avg_max5152float _time; // current timestamp5354bool _armed; // 0 if disarmed, 1 if armed5556float _amp[NUM_FINS]; //amplitudes57float _off[NUM_FINS]; //offsets58float _freq[NUM_FINS]; //frequency multiplier59float _pos[NUM_FINS]; //servo positions6061float _right_amp_factor[NUM_FINS];62float _front_amp_factor[NUM_FINS];63float _down_amp_factor[NUM_FINS];64float _yaw_amp_factor[NUM_FINS];6566float _right_off_factor[NUM_FINS];67float _front_off_factor[NUM_FINS];68float _down_off_factor[NUM_FINS];69float _yaw_off_factor[NUM_FINS];7071int8_t _num_added;7273//MIR This should probably become private in future.74public:75float right_out; //input right movement, negative for left, +1 to -176float front_out; //input front/forwards movement, negative for backwards, +1 to -177float yaw_out; //input yaw, +1 to -178float down_out; //input height control, +1 to -17980AP_Float freq_hz;81AP_Int8 turbo_mode;8283bool _interlock; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)84bool _initialised_ok; // 1 if initialisation was successful8586void output_min();8788void add_fin(int8_t fin_num, float right_amp_fac, float front_amp_fac, float yaw_amp_fac, float down_amp_fac,89float right_off_fac, float front_off_fac, float yaw_off_fac, float down_off_fac);9091void setup_fins();9293void output();9495float get_throttle()96{97//Only for Mavlink - essentially just an indicator of how hard the fins are working.98//Note that this is the unconstrained version, so if the higher level control gives too high input,99//throttle will be displayed as more than 100.100return fmaxf(fmaxf(fabsf(down_out),fabsf(front_out)), fmaxf(fabsf(right_out),fabsf(yaw_out)));101}102103void rc_write(uint8_t chan, uint16_t pwm);104};105106107