uncrustify libraries/RC_Channel/RC_Channel.cpp
This commit is contained in:
parent
02877cfe28
commit
e9fb7cfd92
@ -1,13 +1,13 @@
|
|||||||
/*
|
/*
|
||||||
RC_Channel.cpp - Radio library for Arduino
|
* RC_Channel.cpp - Radio library for Arduino
|
||||||
Code by Jason Short. DIYDrones.com
|
* Code by Jason Short. DIYDrones.com
|
||||||
|
*
|
||||||
This library is free software; you can redistribute it and / or
|
* This library is free software; you can redistribute it and / or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
License as published by the Free Software Foundation; either
|
* License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
@ -141,23 +141,23 @@ RC_Channel::set_pwm(int16_t pwm)
|
|||||||
{
|
{
|
||||||
|
|
||||||
/*if(_filter){
|
/*if(_filter){
|
||||||
if(radio_in == 0)
|
* if(radio_in == 0)
|
||||||
radio_in = pwm;
|
* radio_in = pwm;
|
||||||
else
|
* else
|
||||||
radio_in = (pwm + radio_in) >> 1; // Small filtering
|
* radio_in = (pwm + radio_in) >> 1; // Small filtering
|
||||||
}else{
|
* }else{
|
||||||
radio_in = pwm;
|
* radio_in = pwm;
|
||||||
}*/
|
* }*/
|
||||||
|
|
||||||
radio_in = pwm;
|
radio_in = pwm;
|
||||||
|
|
||||||
if(_type == RC_CHANNEL_RANGE){
|
if(_type == RC_CHANNEL_RANGE) {
|
||||||
control_in = pwm_to_range();
|
control_in = pwm_to_range();
|
||||||
//control_in = constrain(control_in, _low, _high);
|
//control_in = constrain(control_in, _low, _high);
|
||||||
//control_in = min(control_in, _high);
|
//control_in = min(control_in, _high);
|
||||||
control_in = (control_in < _dead_zone) ? 0 : control_in;
|
control_in = (control_in < _dead_zone) ? 0 : control_in;
|
||||||
|
|
||||||
if (fabs(scale_output) != 1){
|
if (fabs(scale_output) != 1) {
|
||||||
control_in *= scale_output;
|
control_in *= scale_output;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -167,17 +167,17 @@ RC_Channel::set_pwm(int16_t pwm)
|
|||||||
control_in = pwm_to_angle();
|
control_in = pwm_to_angle();
|
||||||
|
|
||||||
|
|
||||||
if (fabs(scale_output) != 1){
|
if (fabs(scale_output) != 1) {
|
||||||
control_in *= scale_output;
|
control_in *= scale_output;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
// coming soon ??
|
* // coming soon ??
|
||||||
if(expo) {
|
* if(expo) {
|
||||||
long temp = control_in;
|
* long temp = control_in;
|
||||||
temp = (temp * temp) / (long)_high;
|
* temp = (temp * temp) / (long)_high;
|
||||||
control_in = (int16_t)((control_in >= 0) ? temp : -temp);
|
* control_in = (int16_t)((control_in >= 0) ? temp : -temp);
|
||||||
}*/
|
* }*/
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -198,11 +198,11 @@ RC_Channel::get_failsafe(void)
|
|||||||
void
|
void
|
||||||
RC_Channel::calc_pwm(void)
|
RC_Channel::calc_pwm(void)
|
||||||
{
|
{
|
||||||
if(_type == RC_CHANNEL_RANGE){
|
if(_type == RC_CHANNEL_RANGE) {
|
||||||
pwm_out = range_to_pwm();
|
pwm_out = range_to_pwm();
|
||||||
radio_out = (_reverse >= 0) ? (radio_min + pwm_out) : (radio_max - pwm_out);
|
radio_out = (_reverse >= 0) ? (radio_min + pwm_out) : (radio_max - pwm_out);
|
||||||
|
|
||||||
}else if(_type == RC_CHANNEL_ANGLE_RAW){
|
}else if(_type == RC_CHANNEL_ANGLE_RAW) {
|
||||||
pwm_out = (float)servo_out * .1;
|
pwm_out = (float)servo_out * .1;
|
||||||
radio_out = (pwm_out * _reverse) + radio_trim;
|
radio_out = (pwm_out * _reverse) + radio_trim;
|
||||||
|
|
||||||
@ -263,9 +263,9 @@ RC_Channel::pwm_to_angle()
|
|||||||
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
if(radio_in > radio_trim_high){
|
if(radio_in > radio_trim_high) {
|
||||||
return _reverse * ((long)_high * (long)(radio_in - radio_trim_high)) / (long)(radio_max - radio_trim_high);
|
return _reverse * ((long)_high * (long)(radio_in - radio_trim_high)) / (long)(radio_max - radio_trim_high);
|
||||||
}else if(radio_in < radio_trim_low){
|
}else if(radio_in < radio_trim_low) {
|
||||||
return _reverse * ((long)_high * (long)(radio_in - radio_trim_low)) / (long)(radio_trim_low - radio_min);
|
return _reverse * ((long)_high * (long)(radio_in - radio_trim_low)) / (long)(radio_trim_low - radio_min);
|
||||||
}else
|
}else
|
||||||
return 0;
|
return 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user