mirror of https://github.com/ArduPilot/ardupilot
AP_RC_Channel: deleted this library as nobody seems to be using it.
Everyone is using RC_Channel instead which includes parameters.
This commit is contained in:
parent
c22f3ae563
commit
4e7e78d091
|
@ -1,332 +0,0 @@
|
|||
/*
|
||||
AP_RC_Channel.cpp - Radio library for Arduino Legacy Hardware
|
||||
Code by Jason Short. DIYDrones.com
|
||||
Improvements to implement channel curves by Ron Curry, 2012
|
||||
|
||||
This library is free software; you can redistribute it and / or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
*/
|
||||
|
||||
#include <math.h>
|
||||
#include <avr/eeprom.h>
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
#include "AP_RC_Channel.h"
|
||||
|
||||
#define ANGLE 0
|
||||
#define RANGE 1
|
||||
|
||||
// setup the control preferences
|
||||
void
|
||||
AP_RC_Channel::set_range(int low, int high)
|
||||
{
|
||||
_type = RANGE;
|
||||
_high = high;
|
||||
_low = low;
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::set_angle(int angle)
|
||||
{
|
||||
_type = ANGLE;
|
||||
_high = angle;
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::set_reverse(bool reverse)
|
||||
{
|
||||
if (reverse) _reverse = -1;
|
||||
else _reverse = 1;
|
||||
}
|
||||
|
||||
bool
|
||||
AP_RC_Channel::get_reverse(void)
|
||||
{
|
||||
if (_reverse==-1) return 1;
|
||||
else return 0;
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::set_filter(bool filter)
|
||||
{
|
||||
_filter = filter;
|
||||
}
|
||||
|
||||
// call after first read
|
||||
void
|
||||
AP_RC_Channel::trim()
|
||||
{
|
||||
radio_trim = radio_in;
|
||||
}
|
||||
|
||||
//-------------------------------------------------------------------------------
|
||||
// Support for PWM translation (i.e. curves or "expo")
|
||||
//
|
||||
// Translation of the input PWM is done via a pointer "channel_curve" to an array that defines the PWM output value
|
||||
// for any given input value. The array is structured with element 0 equal to the number of elements
|
||||
// in the curve. If the length is zero then the array defines no curve. If the "channel_curve" pointer
|
||||
// is NULL that is interpretted as no curve defined and is the default state.
|
||||
//
|
||||
// Elements 1 to n of the array contain the values for the curve. These are defined in terms of the actual
|
||||
// PWM output pulsewidth desired for a given point on the curve with curve element 1 containing the value
|
||||
// for the lowest input value from the RC RX and element "n" containing the value for the highest input value
|
||||
// from the RX.
|
||||
//
|
||||
// Input PWM values are expected to be in the range of the radio calibration values "radio_min" to "radio_max". The
|
||||
// user must have already completed the radio calibration otherwise output will be inaccurage. Input PWM values
|
||||
// generate an index that falls between curve elements will cause the output to be interpolated in a linear fashion
|
||||
// between the curve elements. For example: A curve defined as element 0 = 2 (length), element 1 = 900, and
|
||||
// element 2 = 2100 would define a linear straight line output between 900 and 2100 for valid input values.
|
||||
// Additional elements could be inserted between element 1 and element 2 to define more complex
|
||||
// curves. - R. Curry 06-14-12
|
||||
|
||||
|
||||
|
||||
// Sets curve for channel output to user defined curve
|
||||
// Input: curve - A pointer to a user defined output curve for this channel
|
||||
void
|
||||
AP_RC_Channel::set_channel_curve(int *curve)
|
||||
{
|
||||
_channel_curve = curve; // Channel_curve points to array containing curve info
|
||||
}
|
||||
|
||||
// Unsets the curve for this channel - i.e. no curve translation
|
||||
void
|
||||
AP_RC_Channel::unset_channel_curve()
|
||||
{
|
||||
_channel_curve = NULL;
|
||||
}
|
||||
|
||||
|
||||
// Apply the current curve to a PWM value
|
||||
// Input: PWM value in range of radio_min to radio_max
|
||||
// Output: Translated PWM value
|
||||
int
|
||||
AP_RC_Channel::apply_curve(int pwm)
|
||||
{
|
||||
float scale;
|
||||
int index1, index2;
|
||||
|
||||
if (_channel_curve != NULL)
|
||||
{
|
||||
if (_channel_curve[0] > 0) // If the length of the curve isn't zero then use it
|
||||
{
|
||||
// Calculate the index into the channel curve table
|
||||
scale = ((float)(pwm - radio_min) /
|
||||
(float)(radio_max - radio_min)) *
|
||||
((float)_channel_curve[0]-1);
|
||||
index1 = (int)scale; // get the index
|
||||
scale -= (float)index1; // scale now has the remainder for later
|
||||
|
||||
if (index1 < 0) { // If the PWM value below our range then clamp to lowest table entry
|
||||
index1 = 0;
|
||||
scale = 0.0;
|
||||
}
|
||||
|
||||
index2 = index1 + 1; // Point to the next entry beyond our current for interpolation
|
||||
if (index2 >= _channel_curve[0]) { // If we are beyond the end then clamp to highest entry
|
||||
index2 = _channel_curve[0] - 1;
|
||||
if (index1 >= _channel_curve[0]) { // Also check index 1 and clamp if necessary
|
||||
index1 = _channel_curve[0] -1;
|
||||
}
|
||||
}
|
||||
|
||||
// Do the lookup and interpolation
|
||||
index1++; // curve values start at entry 1
|
||||
index2++;
|
||||
pwm = ((_channel_curve[index1] *
|
||||
(1 - scale)) + (_channel_curve[index2] *
|
||||
scale)); // Get the pwm value from the curve and interpolate - done
|
||||
}
|
||||
}
|
||||
|
||||
return pwm; //
|
||||
}
|
||||
|
||||
|
||||
//-------------------------------------------------------------------------------
|
||||
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void
|
||||
AP_RC_Channel::set_pwm(int pwm)
|
||||
{
|
||||
// Serial.print(pwm,DEC);
|
||||
|
||||
// Apply the curve - if any
|
||||
pwm = apply_curve(pwm);
|
||||
|
||||
if(_filter){
|
||||
if(radio_in == 0)
|
||||
radio_in = pwm;
|
||||
else
|
||||
radio_in = ((pwm + radio_in) >> 1); // Small filtering
|
||||
}else{
|
||||
radio_in = pwm;
|
||||
}
|
||||
|
||||
if(_type == RANGE){
|
||||
//Serial.print("range ");
|
||||
control_in = pwm_to_range();
|
||||
control_in = (control_in < dead_zone) ? 0 : control_in;
|
||||
|
||||
}else{
|
||||
control_in = pwm_to_angle();
|
||||
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int
|
||||
AP_RC_Channel::control_mix(float value)
|
||||
{
|
||||
return (1 - abs(control_in / _high)) * value + control_in;
|
||||
}
|
||||
|
||||
// are we below a threshold?
|
||||
bool
|
||||
AP_RC_Channel::get_failsafe(void)
|
||||
{
|
||||
return (radio_in < (radio_min - 50));
|
||||
}
|
||||
|
||||
// returns just the PWM without the offset from radio_min
|
||||
void
|
||||
AP_RC_Channel::calc_pwm(void)
|
||||
{
|
||||
|
||||
if(_type == RANGE){
|
||||
pwm_out = range_to_pwm();
|
||||
radio_out = pwm_out + radio_min;
|
||||
}else{
|
||||
pwm_out = angle_to_pwm();
|
||||
radio_out = pwm_out + radio_trim;
|
||||
}
|
||||
// radio_out = constrain(radio_out, radio_min, radio_max);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
||||
void
|
||||
AP_RC_Channel::load_eeprom(void)
|
||||
{
|
||||
radio_min = eeprom_read_word((uint16_t *) _address);
|
||||
radio_max = eeprom_read_word((uint16_t *) (_address + 2));
|
||||
load_trim();
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::save_eeprom(void)
|
||||
{
|
||||
eeprom_write_word((uint16_t *) _address, radio_min);
|
||||
eeprom_write_word((uint16_t *) (_address + 2), radio_max);
|
||||
save_trim();
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
void
|
||||
AP_RC_Channel::save_trim(void)
|
||||
{
|
||||
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::load_trim(void)
|
||||
{
|
||||
radio_trim = eeprom_read_word((uint16_t *) (_address + 4));
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
||||
void
|
||||
AP_RC_Channel::zero_min_max()
|
||||
{
|
||||
radio_min = radio_max = radio_in;
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC_Channel::update_min_max()
|
||||
{
|
||||
radio_min = min(radio_min, radio_in);
|
||||
radio_max = max(radio_max, radio_in);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
||||
int16_t
|
||||
AP_RC_Channel::pwm_to_angle()
|
||||
{
|
||||
if(radio_in < radio_trim)
|
||||
return _reverse * ((long)_high * (long)(radio_in - radio_trim)) / (long)(radio_trim - radio_min);
|
||||
else
|
||||
return _reverse * ((long)_high * (long)(radio_in - radio_trim)) / (long)(radio_max - radio_trim);
|
||||
|
||||
//return _reverse * _high * ((float)(radio_in - radio_trim) / (float)(radio_max - radio_trim));
|
||||
//return _reverse * _high * ((float)(radio_in - radio_trim) / (float)(radio_trim - radio_min));
|
||||
}
|
||||
|
||||
|
||||
int16_t
|
||||
AP_RC_Channel::angle_to_pwm()
|
||||
{
|
||||
if(_reverse == -1)
|
||||
{
|
||||
if(servo_out < 0)
|
||||
return ( -1 * ((long)servo_out * (long)(radio_max - radio_trim)) / (long)_high);
|
||||
else
|
||||
return ( -1 * ((long)servo_out * (long)(radio_trim - radio_min)) / (long)_high);
|
||||
} else {
|
||||
if(servo_out > 0)
|
||||
return ((long)servo_out * (long)(radio_max - radio_trim)) / (long)_high;
|
||||
else
|
||||
return ((long)servo_out * (long)(radio_trim - radio_min)) / (long)_high;
|
||||
}
|
||||
|
||||
//return (((float)servo_out / (float)_high) * (float)(radio_max - radio_trim));
|
||||
//return (((float)servo_out / (float)_high) * (float)(radio_trim - radio_min));
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
||||
int16_t
|
||||
AP_RC_Channel::pwm_to_range()
|
||||
{
|
||||
//return (_low + ((_high - _low) * ((float)(radio_in - radio_min) / (float)(radio_max - radio_min))));
|
||||
return (_low + ((long)(_high - _low) * (long)(radio_in - radio_min)) / (long)(radio_max - radio_min));
|
||||
}
|
||||
|
||||
int16_t
|
||||
AP_RC_Channel::range_to_pwm()
|
||||
{
|
||||
//return (((float)(servo_out - _low) / (float)(_high - _low)) * (float)(radio_max - radio_min));
|
||||
return ((long)(servo_out - _low) * (long)(radio_max - radio_min)) / (long)(_high - _low);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
||||
float
|
||||
AP_RC_Channel::norm_input()
|
||||
{
|
||||
if(radio_in < radio_trim)
|
||||
return _reverse * (float)(radio_in - radio_trim) / (float)(radio_trim - radio_min);
|
||||
else
|
||||
return _reverse * (float)(radio_in - radio_trim) / (float)(radio_max - radio_trim);
|
||||
}
|
||||
|
||||
float
|
||||
AP_RC_Channel::norm_output()
|
||||
{
|
||||
if(radio_out < radio_trim)
|
||||
return (float)(radio_out - radio_trim) / (float)(radio_trim - radio_min);
|
||||
else
|
||||
return (float)(radio_out - radio_trim) / (float)(radio_max - radio_trim);
|
||||
}
|
|
@ -1,106 +0,0 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file AP_RC_Channel.h
|
||||
/// @brief AP_RC_Channel manager, with EEPROM-backed storage of constants.
|
||||
|
||||
#ifndef AP_RC_Channel_h
|
||||
#define AP_RC_Channel_h
|
||||
|
||||
//#include <AP_Common.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/// @class AP_RC_Channel
|
||||
/// @brief Object managing one RC channel
|
||||
class AP_RC_Channel{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key EEPROM storage key for the channel trim parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
AP_RC_Channel(uint16_t address) :
|
||||
_address(address),
|
||||
_high(1),
|
||||
_filter(true),
|
||||
_reverse(1),
|
||||
dead_zone(0){}
|
||||
|
||||
AP_RC_Channel() :
|
||||
_high(1),
|
||||
_filter(true),
|
||||
_reverse(1),
|
||||
dead_zone(0){}
|
||||
|
||||
// setup min and max radio values in CLI
|
||||
void update_min_max();
|
||||
void zero_min_max();
|
||||
|
||||
// startup
|
||||
void load_eeprom(void);
|
||||
void save_eeprom(void);
|
||||
void save_trim(void);
|
||||
void load_trim(void);
|
||||
void set_filter(bool filter);
|
||||
|
||||
// setup the control preferences
|
||||
void set_range(int low, int high);
|
||||
void set_angle(int angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int pwm);
|
||||
|
||||
// pwm is stored here
|
||||
int16_t radio_in;
|
||||
|
||||
// call after first set_pwm
|
||||
void trim();
|
||||
|
||||
// did our read come in 50µs below the min?
|
||||
bool get_failsafe(void);
|
||||
|
||||
// value generated from PWM
|
||||
int16_t control_in;
|
||||
int16_t dead_zone; // used to keep noise down and create a dead zone.
|
||||
|
||||
int control_mix(float value);
|
||||
|
||||
// current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100
|
||||
int16_t servo_out;
|
||||
|
||||
// generate PWM from servo_out value
|
||||
void calc_pwm(void);
|
||||
|
||||
// PWM is without the offset from radio_min
|
||||
int16_t pwm_out;
|
||||
int16_t radio_out;
|
||||
|
||||
int16_t radio_min;
|
||||
int16_t radio_trim;
|
||||
int16_t radio_max;
|
||||
|
||||
// includes offset from PWM
|
||||
//int16_t get_radio_out(void);
|
||||
|
||||
int16_t pwm_to_angle();
|
||||
float norm_input();
|
||||
float norm_output();
|
||||
int16_t angle_to_pwm();
|
||||
int16_t pwm_to_range();
|
||||
int16_t range_to_pwm();
|
||||
|
||||
private:
|
||||
bool _filter;
|
||||
int8_t _reverse;
|
||||
int16_t _address;
|
||||
bool _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
@ -1,353 +0,0 @@
|
|||
/*
|
||||
Example of AP_RC_Channel library.
|
||||
Original Code by Jason Short. 2010
|
||||
Updates to support 2.6+ and channel curves by Ron Curry, 2012
|
||||
DIYDrones.com
|
||||
|
||||
*/
|
||||
|
||||
#include <AP_RC_Channel.h> // ArduPilot RC Library
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
APM_RC_APM2 APM_RC;
|
||||
/*
|
||||
#define EE_RADIO_1 0x00 // all gains stored from here
|
||||
#define EE_RADIO_2 0x06 // all gains stored from here
|
||||
#define EE_RADIO_3 0x0C // all gains stored from here
|
||||
#define EE_RADIO_4 0x12 // all gains stored from here
|
||||
|
||||
AP_RC_Channel rc_1(EE_RADIO_1);
|
||||
AP_RC_Channel rc_2(EE_RADIO_2);
|
||||
AP_RC_Channel rc_3(EE_RADIO_3);
|
||||
AP_RC_Channel rc_4(EE_RADIO_4);
|
||||
*/
|
||||
AP_RC_Channel rc_1;
|
||||
AP_RC_Channel rc_2;
|
||||
AP_RC_Channel rc_3;
|
||||
AP_RC_Channel rc_4;
|
||||
AP_RC_Channel rc_5;
|
||||
AP_RC_Channel rc_6;
|
||||
AP_RC_Channel rc_7;
|
||||
AP_RC_Channel rc_8;
|
||||
|
||||
// curve1 demonstrates how the full range of the RC input is scaled to span only a range of 200 with increased resolution
|
||||
// Output is not clipped but rather scaled
|
||||
static int curve1[] = { 3, 1400, 1500, 1600};
|
||||
|
||||
// curve2 demonstrates quick ramp with short throw from 1100 to 1400, then flat, high-res section from 1400 - 1600, then quick
|
||||
// ramp short throw from 1600 to 1950 - classic expo function as seen in most TX's
|
||||
static int curve2[] = {5, 1100, 1400, 1500, 1600, 1950};
|
||||
|
||||
// curve 3 demonstrats quick ramp/short thrown to 1300 then relative flat, high-rese section from 1300 to 1950 with a more
|
||||
// detailed definition
|
||||
static int curve3[] = {10, 1100, 1300, 1400, 1450, 1500, 1550, 1600, 1700, 1825, 1950};
|
||||
|
||||
// curve 4 demonstrates scaling to a larger PWM range in this case 900-2100 (from approx 1100-1900)
|
||||
// with other modifications this could be used to support output devices that require a different range of PWM values than normal
|
||||
static int curve4[] = {3, 100, 500, 900};
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
isr_registry.init();
|
||||
APM_RC.Init(&isr_registry); // APM Radio initialization
|
||||
|
||||
APM_RC.enable_out(CH_1);
|
||||
APM_RC.enable_out(CH_2);
|
||||
APM_RC.enable_out(CH_3);
|
||||
APM_RC.enable_out(CH_4);
|
||||
APM_RC.enable_out(CH_5);
|
||||
APM_RC.enable_out(CH_6);
|
||||
APM_RC.enable_out(CH_7);
|
||||
APM_RC.enable_out(CH_8);
|
||||
|
||||
|
||||
Serial.begin(115200);
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
delay(500);
|
||||
|
||||
// setup radio
|
||||
|
||||
// read eepom or set manually
|
||||
/*
|
||||
rc_1.radio_min = 1100;
|
||||
rc_1.radio_max = 1900;
|
||||
|
||||
rc_2.radio_min = 1100;
|
||||
rc_2.radio_max = 1900;
|
||||
|
||||
rc_3.radio_min = 1100;
|
||||
rc_3.radio_max = 1900;
|
||||
|
||||
rc_4.radio_min = 1100;
|
||||
rc_4.radio_max = 1900;
|
||||
|
||||
// or
|
||||
|
||||
rc_1.load_eeprom();
|
||||
rc_2.load_eeprom();
|
||||
rc_3.load_eeprom();
|
||||
rc_4.load_eeprom();
|
||||
|
||||
*/
|
||||
|
||||
// interactive setup
|
||||
setup_radio();
|
||||
|
||||
print_radio_values();
|
||||
|
||||
// set type of output, symmetrical angles or a number range;
|
||||
rc_1.set_range(0,1000);
|
||||
rc_2.set_range(0,1000);
|
||||
rc_3.set_range(0,1000);
|
||||
rc_4.set_range(0,1000);
|
||||
rc_5.set_range(0,1000);
|
||||
rc_6.set_angle(4500);
|
||||
rc_7.set_angle(4500);
|
||||
rc_8.set_angle(4500);
|
||||
/*
|
||||
rc_1.dead_zone = 85;
|
||||
rc_2.dead_zone = 85;
|
||||
rc_3.dead_zone = 85;
|
||||
rc_4.dead_zone = 85;
|
||||
rc_5.dead_zone = 85;
|
||||
rc_6.dead_zone = 85;
|
||||
rc_7.dead_zone = 85;
|
||||
rc_8.dead_zone = 85;
|
||||
*/
|
||||
for (byte i = 0; i < 30; i++){
|
||||
read_radio();
|
||||
}
|
||||
rc_1.trim();
|
||||
rc_2.trim();
|
||||
rc_4.trim();
|
||||
rc_5.trim();
|
||||
rc_6.trim();
|
||||
rc_7.trim();
|
||||
rc_8.trim();
|
||||
|
||||
// Setup test curves
|
||||
rc_1.set_channel_curve(curve1);
|
||||
rc_2.set_channel_curve(curve2);
|
||||
rc_3.set_channel_curve(curve3);
|
||||
rc_4.set_channel_curve(curve4);
|
||||
rc_5.unset_channel_curve();
|
||||
rc_6.unset_channel_curve();
|
||||
rc_7.unset_channel_curve();
|
||||
rc_8.unset_channel_curve();
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
if (APM_RC.GetState() == 1)
|
||||
{
|
||||
read_radio();
|
||||
rc_1.servo_out = rc_1.control_in;
|
||||
rc_2.servo_out = rc_2.control_in;
|
||||
rc_3.servo_out = rc_3.control_in;
|
||||
rc_4.servo_out = rc_4.control_in;
|
||||
rc_5.servo_out = rc_5.control_in;
|
||||
rc_6.servo_out = rc_6.control_in;
|
||||
rc_7.servo_out = rc_7.control_in;
|
||||
rc_8.servo_out = rc_8.control_in;
|
||||
|
||||
|
||||
rc_1.calc_pwm();
|
||||
rc_2.calc_pwm();
|
||||
rc_3.calc_pwm();
|
||||
rc_4.calc_pwm();
|
||||
rc_5.calc_pwm();
|
||||
rc_6.calc_pwm();
|
||||
rc_7.calc_pwm();
|
||||
rc_8.calc_pwm();
|
||||
|
||||
print_pwm();
|
||||
print_control_in();
|
||||
|
||||
// send values to the PWM timers for output
|
||||
// ----------------------------------------
|
||||
APM_RC.OutputCh(CH_1, rc_1.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_2, rc_2.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_3, rc_3.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_4, rc_4.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_5, rc_5.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_6, rc_6.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_7, rc_7.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_8, rc_8.radio_out); // send to Servos
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void read_radio()
|
||||
{
|
||||
rc_1.set_pwm(APM_RC.InputCh(CH_1));
|
||||
rc_2.set_pwm(APM_RC.InputCh(CH_2));
|
||||
rc_3.set_pwm(APM_RC.InputCh(CH_3));
|
||||
rc_4.set_pwm(APM_RC.InputCh(CH_4));
|
||||
rc_5.set_pwm(APM_RC.InputCh(CH_5));
|
||||
rc_6.set_pwm(APM_RC.InputCh(CH_6));
|
||||
rc_7.set_pwm(APM_RC.InputCh(CH_7));
|
||||
rc_8.set_pwm(APM_RC.InputCh(CH_8));
|
||||
//Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"), rc_1.control_in, rc_2.control_in, rc_3.control_in, rc_4.control_in,
|
||||
// rc_5.control_in, rc_6.control_in, rc_7.control_in, rc_8.control_in);
|
||||
}
|
||||
|
||||
void print_pwm()
|
||||
{
|
||||
Serial.print("\t1: ");
|
||||
Serial.print(rc_1.radio_out, DEC);
|
||||
Serial.print("\t2: ");
|
||||
Serial.print(rc_2.radio_out, DEC);
|
||||
Serial.print("\t3:");
|
||||
Serial.print(rc_3.radio_out, DEC);
|
||||
Serial.print("\t4:");
|
||||
Serial.print(rc_4.radio_in , DEC);
|
||||
/* Serial.print("\t5");
|
||||
Serial.print(rc_5.radio_out, DEC);
|
||||
Serial.print("\t6: ");
|
||||
Serial.print(rc_6.radio_out, DEC);
|
||||
Serial.print("\t7:");
|
||||
Serial.print(rc_7.radio_out, DEC);
|
||||
Serial.print("\t8:");
|
||||
Serial.print(rc_8.radio_out , DEC);
|
||||
*/
|
||||
}
|
||||
|
||||
// 1280
|
||||
// 1536
|
||||
// 1795
|
||||
void print_control_in()
|
||||
{
|
||||
Serial.print("\t1: ");
|
||||
Serial.print(rc_1.control_in, DEC);
|
||||
Serial.print("\t2: ");
|
||||
Serial.print(rc_2.control_in, DEC);
|
||||
Serial.print("\t3:");
|
||||
Serial.print(rc_3.control_in, DEC);
|
||||
Serial.print("\t4:");
|
||||
Serial.println(rc_4.control_in, DEC);
|
||||
/* Serial.print("\t5: ");
|
||||
Serial.print(rc_5.control_in, DEC);
|
||||
Serial.print("\t6: ");
|
||||
Serial.print(rc_6.control_in, DEC);
|
||||
Serial.print("\t7:");
|
||||
Serial.print(rc_7.control_in, DEC);
|
||||
Serial.print("\t8:");
|
||||
Serial.println(rc_8.control_in, DEC);
|
||||
*/
|
||||
}
|
||||
|
||||
void
|
||||
print_radio_values()
|
||||
{
|
||||
Serial.print("CH1: ");
|
||||
Serial.print(rc_1.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_1.radio_max, DEC);
|
||||
|
||||
Serial.print("CH2: ");
|
||||
Serial.print(rc_2.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_2.radio_max, DEC);
|
||||
|
||||
Serial.print("CH3: ");
|
||||
Serial.print(rc_3.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_3.radio_max, DEC);
|
||||
|
||||
Serial.print("CH4: ");
|
||||
Serial.print(rc_4.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_4.radio_max, DEC);
|
||||
/*
|
||||
Serial.print("CH5: ");
|
||||
Serial.print(rc_5.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_5.radio_max, DEC);
|
||||
|
||||
Serial.print("CH6: ");
|
||||
Serial.print(rc_6.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_6.radio_max, DEC);
|
||||
|
||||
Serial.print("CH7: ");
|
||||
Serial.print(rc_7.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_7.radio_max, DEC);
|
||||
|
||||
Serial.print("CH8: ");
|
||||
Serial.print(rc_8.radio_min, DEC);
|
||||
Serial.print(" | ");
|
||||
Serial.println(rc_8.radio_max, DEC);
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
setup_radio()
|
||||
{
|
||||
Serial.println("\n\nRadio Setup:");
|
||||
uint8_t i;
|
||||
|
||||
for(i = 0; i < 100;i++){
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
rc_1.radio_min = rc_1.radio_in;
|
||||
rc_2.radio_min = rc_2.radio_in;
|
||||
rc_3.radio_min = rc_3.radio_in;
|
||||
rc_4.radio_min = rc_4.radio_in;
|
||||
rc_5.radio_min = rc_5.radio_in;
|
||||
rc_6.radio_min = rc_6.radio_in;
|
||||
rc_7.radio_min = rc_7.radio_in;
|
||||
rc_8.radio_min = rc_8.radio_in;
|
||||
|
||||
rc_1.radio_max = rc_1.radio_in;
|
||||
rc_2.radio_max = rc_2.radio_in;
|
||||
rc_3.radio_max = rc_3.radio_in;
|
||||
rc_4.radio_max = rc_4.radio_in;
|
||||
rc_5.radio_max = rc_5.radio_in;
|
||||
rc_6.radio_max = rc_6.radio_in;
|
||||
rc_7.radio_max = rc_7.radio_in;
|
||||
rc_8.radio_max = rc_8.radio_in;
|
||||
|
||||
rc_1.radio_trim = rc_1.radio_in;
|
||||
rc_2.radio_trim = rc_2.radio_in;
|
||||
rc_4.radio_trim = rc_4.radio_in;
|
||||
rc_5.radio_trim = rc_5.radio_in;
|
||||
rc_6.radio_trim = rc_6.radio_in;
|
||||
rc_7.radio_trim = rc_7.radio_in;
|
||||
rc_8.radio_trim = rc_8.radio_in;
|
||||
|
||||
Serial.println("\nMove all controls to each extreme. Hit Enter to save:");
|
||||
while(1){
|
||||
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
|
||||
rc_1.update_min_max();
|
||||
rc_2.update_min_max();
|
||||
rc_3.update_min_max();
|
||||
rc_4.update_min_max();
|
||||
rc_5.update_min_max();
|
||||
rc_6.update_min_max();
|
||||
rc_7.update_min_max();
|
||||
rc_8.update_min_max();
|
||||
|
||||
if(Serial.available() > 0){
|
||||
//rc_3.radio_max += 250;
|
||||
Serial.flush();
|
||||
|
||||
Serial.println("Radio calibrated, Showing control values:");
|
||||
break;
|
||||
}
|
||||
}
|
||||
return;
|
||||
}
|
|
@ -1,2 +0,0 @@
|
|||
BOARD = mega
|
||||
include ../../../AP_Common/Arduino.mk
|
Loading…
Reference in New Issue