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.cpp
Views: 1798
#include "Blimp.h"12#include <SRV_Channel/SRV_Channel.h>34// This is the scale used for RC inputs so that they can be scaled to the float point values used in the sine wave code.5#define FIN_SCALE_MAX 100067/*82nd group of parameters9*/10const AP_Param::GroupInfo Fins::var_info[] = {1112// @Param: FREQ_HZ13// @DisplayName: Fins frequency14// @Description: This is the oscillation frequency of the fins15// @Range: 1 1016// @User: Standard17AP_GROUPINFO("FREQ_HZ", 1, Fins, freq_hz, 3),1819// @Param: TURBO_MODE20// @DisplayName: Enable turbo mode21// @Description: Enables double speed on high offset.22// @Range: 0 123// @User: Standard24AP_GROUPINFO("TURBO_MODE", 2, Fins, turbo_mode, 0),2526AP_GROUPEND27};2829//constructor30Fins::Fins(uint16_t loop_rate) :31_loop_rate(loop_rate)32{33AP_Param::setup_object_defaults(this, var_info);34}3536void Fins::setup_fins()37{38//fin # r f d y, r f d y right, front, down, yaw for amplitude then for offset39add_fin(0, 0, 1, 0.5, 0, 0, 0, 0.5, 0); //Back40add_fin(1, 0, -1, 0.5, 0, 0, 0, 0.5, 0); //Front41add_fin(2, -1, 0, 0, 0.5, 0, 0, 0, 0.5); //Right42add_fin(3, 1, 0, 0, 0.5, 0, 0, 0, -0.5); //Left4344SRV_Channels::set_angle(SRV_Channel::k_motor1, FIN_SCALE_MAX);45SRV_Channels::set_angle(SRV_Channel::k_motor2, FIN_SCALE_MAX);46SRV_Channels::set_angle(SRV_Channel::k_motor3, FIN_SCALE_MAX);47SRV_Channels::set_angle(SRV_Channel::k_motor4, FIN_SCALE_MAX);48}4950void Fins::add_fin(int8_t fin_num, float right_amp_fac, float front_amp_fac, float down_amp_fac, float yaw_amp_fac,51float right_off_fac, float front_off_fac, float down_off_fac, float yaw_off_fac)52{5354// ensure valid fin number is provided55if (fin_num >= 0 && fin_num < NUM_FINS) {5657// set amplitude factors58_right_amp_factor[fin_num] = right_amp_fac;59_front_amp_factor[fin_num] = front_amp_fac;60_down_amp_factor[fin_num] = down_amp_fac;61_yaw_amp_factor[fin_num] = yaw_amp_fac;6263// set offset factors64_right_off_factor[fin_num] = right_off_fac;65_front_off_factor[fin_num] = front_off_fac;66_down_off_factor[fin_num] = down_off_fac;67_yaw_off_factor[fin_num] = yaw_off_fac;68}69}7071//B,F,R,L = 0,1,2,372void Fins::output()73{74if (!_armed) {75// set everything to zero so fins stop moving76right_out = 0;77front_out = 0;78down_out = 0;79yaw_out = 0;80}8182#if HAL_LOGGING_ENABLED83blimp.Write_FINI(right_out, front_out, down_out, yaw_out);84#endif8586//Constrain after logging so as to still show when sub-optimal tuning is causing massive overshoots.87right_out = constrain_float(right_out, -1, 1);88front_out = constrain_float(front_out, -1, 1);89down_out = constrain_float(down_out, -1, 1);90yaw_out = constrain_float(yaw_out, -1, 1);9192_time = AP_HAL::micros() * 1.0e-6;9394for (int8_t i=0; i<NUM_FINS; i++) {95_amp[i] = fmaxf(0,_right_amp_factor[i]*right_out) + fmaxf(0,_front_amp_factor[i]*front_out) +96fabsf(_down_amp_factor[i]*down_out) + fabsf(_yaw_amp_factor[i]*yaw_out);97_off[i] = _right_off_factor[i]*right_out + _front_off_factor[i]*front_out +98_down_off_factor[i]*down_out + _yaw_off_factor[i]*yaw_out;99_freq[i] = 1;100101_num_added = 0;102if (fmaxf(0,_right_amp_factor[i]*right_out) > 0.0f) {103_num_added++;104}105if (fmaxf(0,_front_amp_factor[i]*front_out) > 0.0f) {106_num_added++;107}108if (fabsf(_down_amp_factor[i]*down_out) > 0.0f) {109_num_added++;110}111if (fabsf(_yaw_amp_factor[i]*yaw_out) > 0.0f) {112_num_added++;113}114115if (_num_added > 0) {116_off[i] = _off[i]/_num_added; //average the offsets117}118119if ((_amp[i]+fabsf(_off[i])) > 1) {120_amp[i] = 1 - fabsf(_off[i]);121}122123if (turbo_mode) {124//double speed fins if offset at max...125if (_amp[i] <= 0.6 && fabsf(_off[i]) >= 0.4) {126_freq[i] = 2;127}128}129// finding and outputting current position for each servo from sine wave130_pos[i]= _amp[i]*cosf(freq_hz * _freq[i] * _time * 2 * M_PI) + _off[i];131SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), _pos[i] * FIN_SCALE_MAX);132}133134#if HAL_LOGGING_ENABLED135blimp.Write_FINO(_amp, _off);136#endif137}138139void Fins::output_min()140{141right_out = 0;142front_out = 0;143down_out = 0;144yaw_out = 0;145Fins::output();146}147148149