mirror of https://github.com/ArduPilot/ardupilot
Working on RC_ChannelB example.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1260 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b88d96d111
commit
de5c16722a
|
@ -101,7 +101,7 @@ public:
|
|||
/**
|
||||
* The default constrcutor
|
||||
*/
|
||||
AP_EEPromVar(type data, const char * name = "", bool sync=false) :
|
||||
AP_EEPromVar(type data = 0, const char * name = "", bool sync=false) :
|
||||
AP_Var<type>(data,name,sync)
|
||||
{
|
||||
eepromRegistry.add(this,_id,_address,sizeof(type));
|
||||
|
|
|
@ -11,12 +11,10 @@
|
|||
|
||||
#include <math.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include "WProgram.h"
|
||||
#include "RC_ChannelB.h"
|
||||
#include <AP_Common.h>
|
||||
|
||||
void
|
||||
RC_ChannelB::readRadio(uint16_t pwmRadio)
|
||||
{
|
||||
void RC_ChannelB::readRadio(uint16_t pwmRadio) {
|
||||
// apply reverse
|
||||
if(_reverse) _pwmRadio = (_pwmNeutral - pwmRadio) + _pwmNeutral;
|
||||
else _pwmRadio = pwmRadio;
|
||||
|
@ -77,34 +75,4 @@ RC_ChannelB::_pwmToPosition(uint16_t pwm)
|
|||
return _scale * (_pwm - _pwmNeutral)/(_pwmMax - _pwmNeutral);
|
||||
}
|
||||
|
||||
void
|
||||
RC_ChannelB::loadEEProm()
|
||||
{
|
||||
if (_storageType == STORE_EEPROM)
|
||||
{
|
||||
eeprom_read_block((void*)&_scale,(const void*)(_address),sizeof(_scale));
|
||||
eeprom_read_block((void*)&_pwmMin,(const void*)(_address + 4),sizeof(_pwmMin));
|
||||
eeprom_read_block((void*)&_pwmMax,(const void*)(_address + 6),sizeof(_pwmMax));
|
||||
eeprom_read_block((void*)&_pwmNeutral,(const void*)(_address + 8),sizeof(_pwmNeutral));
|
||||
eeprom_read_block((void*)&_pwmDeadZone,(const void*)(_address + 10),sizeof(_pwmDeadZone));
|
||||
eeprom_read_block((void*)&_filter,(const void*)(_address+12),sizeof(_filter));
|
||||
eeprom_read_block((void*)&_pwmDeadZone,(const void*)(_address+13),sizeof(_pwmDeadZone));
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
RC_ChannelB::saveEEProm()
|
||||
{
|
||||
if (_storageType == STORE_EEPROM)
|
||||
{
|
||||
eeprom_write_block((const void*)&_scale,(void*)(_address),sizeof(_scale));
|
||||
eeprom_write_block((const void*)&_pwmMin,(void*)(_address + 4),sizeof(_pwmMin));
|
||||
eeprom_write_block((const void*)&_pwmMax,(void*)(_address + 6),sizeof(_pwmMax));
|
||||
eeprom_write_block((const void*)&_pwmNeutral,(void*)(_address + 8),sizeof(_pwmNeutral));
|
||||
eeprom_write_block((const void*)&_pwmDeadZone,(void*)(_address + 10),sizeof(_pwmDeadZone));
|
||||
eeprom_write_block((const void*)&_filter,(void*)(_address+12),sizeof(_filter));
|
||||
eeprom_write_block((const void*)&_pwmDeadZone,(void*)(_address+13),sizeof(_pwmDeadZone));
|
||||
}
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
|
|
@ -7,94 +7,32 @@
|
|||
#define RC_ChannelB_h
|
||||
|
||||
#include <stdint.h>
|
||||
#include <AP_EEProm.h>
|
||||
#include <FastSerial.h>
|
||||
|
||||
/// @class RC_ChannelB
|
||||
/// @brief Object managing one RC channel
|
||||
//
|
||||
class RC_ChannelB{
|
||||
|
||||
public:
|
||||
|
||||
enum storage_t
|
||||
{
|
||||
STORE_EXTERNAL,
|
||||
STORE_EEPROM
|
||||
};
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
RC_ChannelB() :
|
||||
_scale(0),
|
||||
_pwmMin(1000),
|
||||
_pwmMax(2000),
|
||||
_pwmNeutral(1500),
|
||||
_pwmDeadZone(100),
|
||||
RC_ChannelB(const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral,
|
||||
const uint16_t & pwmMax, const uint16_t & pwmDeadZone,
|
||||
const bool & filter, const bool & reverse) :
|
||||
_scale(scale),
|
||||
_pwmMin(pwmMin),
|
||||
_pwmMax(pwmMax),
|
||||
_pwmNeutral(pwmNeutral),
|
||||
_pwmDeadZone(pwmDeadZone),
|
||||
_pwm(0),
|
||||
_pwmRadio(0),
|
||||
_filter(true),
|
||||
_reverse(false),
|
||||
_address(0),
|
||||
_storageType(STORE_EXTERNAL)
|
||||
_filter(filter),
|
||||
_reverse(reverse)
|
||||
{
|
||||
}
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
RC_ChannelB() :
|
||||
_scale(0),
|
||||
_pwmMin(1000),
|
||||
_pwmNeutral(1500),
|
||||
_pwmMax(2000),
|
||||
_pwmDeadZone(100),
|
||||
_pwm(0),
|
||||
_pwmRadio(0),
|
||||
_filter(true),
|
||||
_reverse(false),
|
||||
_address(address),
|
||||
_storageType(STORE_EEPROM)
|
||||
{
|
||||
}
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
RC_ChannelB(uint16_t address) :
|
||||
_scale(0),
|
||||
_pwmMin(1000),
|
||||
_pwmNeutral(1500),
|
||||
_pwmMax(2000),
|
||||
_pwmDeadZone(100),
|
||||
_pwm(0),
|
||||
_pwmRadio(0),
|
||||
_filter(true),
|
||||
_reverse(false),
|
||||
_address(address),
|
||||
_storageType(STORE_EEPROM)
|
||||
{
|
||||
}
|
||||
|
||||
// set configuration
|
||||
void setScale(float scale) { _scale = scale; }
|
||||
void setReverse(bool reverse) { _reverse = reverse; }
|
||||
void setFilter(bool filter) { _filter = filter; }
|
||||
void setPwmMin(uint16_t pwmMin) { _pwmMin = pwmMin; }
|
||||
void setPwmMax(uint16_t pwmMax) { _pwmMax = pwmMax; }
|
||||
void setPwmNeutral(uint16_t pwmNeutral) { _pwmNeutral = pwmNeutral; }
|
||||
void setPwmNeutral() { _pwmNeutral = getPwm(); }
|
||||
void setPwmDeadZone(uint16_t pwmDeadZone) { _pwmDeadZone = pwmDeadZone; }
|
||||
|
||||
// save/load
|
||||
void saveEEProm();
|
||||
void loadEEProm();
|
||||
|
||||
// get configuration
|
||||
float getScale() { return _scale; }
|
||||
bool getReverse() { return _reverse; }
|
||||
bool getFilter() { return _filter; }
|
||||
uint16_t getPwmMin() { return _pwmMin; }
|
||||
uint16_t getPwmMax() { return _pwmMax; }
|
||||
uint16_t getPwmNeutral() { return _pwmNeutral; }
|
||||
uint16_t getPwmDeadZone() { return _pwmDeadZone; }
|
||||
|
||||
// set servo state
|
||||
void readRadio(uint16_t pwmRadio);
|
||||
void setPwm(uint16_t pwm);
|
||||
|
@ -112,19 +50,18 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
float _scale;
|
||||
AP_EEProm<uint16_t> _pwmMin;
|
||||
uint16_t _pwmNeutral;
|
||||
uint16_t _pwmMax;
|
||||
uint16_t _pwmDeadZone;
|
||||
// configuration
|
||||
const float & _scale;
|
||||
const uint16_t & _pwmMin;
|
||||
const uint16_t & _pwmNeutral;
|
||||
const uint16_t & _pwmMax;
|
||||
const uint16_t & _pwmDeadZone;
|
||||
const bool & _filter;
|
||||
const int8_t & _reverse;
|
||||
|
||||
// internal states
|
||||
uint16_t _pwm; // this is the internal state, positino is just created when needed
|
||||
uint16_t _pwmRadio; // radio pwm input
|
||||
|
||||
// configuration
|
||||
bool _filter;
|
||||
int8_t _reverse;
|
||||
storage_t _storageType;
|
||||
uint16_t _address;
|
||||
|
||||
// private methods
|
||||
uint16_t _positionToPwm(float position);
|
||||
|
|
|
@ -1,18 +1,35 @@
|
|||
/*
|
||||
Example of RC_Channel library.
|
||||
Code by Jason Short. 2010
|
||||
Code by James Goppert. 2010
|
||||
DIYDrones.com
|
||||
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <RC_ChannelB.h> // ArduPilot Mega RC Library
|
||||
#include <AP_Common.h>
|
||||
#include <AP_EEProm.h>
|
||||
|
||||
AP_EEPromVar<float> scale(45.0,"RC1_SCALE");
|
||||
AP_EEPromVar<uint16_t> pwmMin(1000,"RC1_PWMMIN");
|
||||
AP_EEPromVar<uint16_t> pwmNeutral(1500,"RC1_PWMNEUTRAL");
|
||||
AP_EEPromVar<uint16_t> pwmMax(2000,"RC1_PWMMAX");
|
||||
AP_EEPromVar<uint16_t> pwmDeadZone(100,"RC1_PWMDEADZONE");
|
||||
|
||||
#define CH_1 0
|
||||
|
||||
// configuration
|
||||
AP_Var<bool> filter(true,"RC1_FILTER");
|
||||
AP_Var<int8_t> reverse(false,"RC1_REVERSE");
|
||||
|
||||
FastSerialPort0(Serial);
|
||||
|
||||
RC_ChannelB rc[] =
|
||||
{
|
||||
RC_ChannelB()
|
||||
RC_ChannelB(scale.get(),pwmMin.get(),pwmNeutral.get(),pwmMax.get(),
|
||||
pwmDeadZone.get(),filter.get(),reverse.get())
|
||||
|
||||
};
|
||||
|
||||
void setup()
|
||||
|
@ -22,12 +39,29 @@ void setup()
|
|||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
delay(1000);
|
||||
// setup radio
|
||||
|
||||
// setup radio
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Serial.println("looping");
|
||||
delay(1000);
|
||||
rc[CH_1].readRadio(APM_RC.InputCh(CH_1));
|
||||
Serial.printf("\nrc[CH_1].readRadio(APM_RC.InputCh(CH_1))\n");
|
||||
Serial.printf("pwm: %d position: %f\n",rc[CH_1].getPwm(), rc[CH_1].getPosition());
|
||||
delay(2000);
|
||||
|
||||
scale.set(100);
|
||||
Serial.printf("\nscale.set(100)\n");
|
||||
|
||||
|
||||
rc[CH_1].setPwm(1500);
|
||||
Serial.printf("\nrc[CH_1].setPwm(1500)\n");
|
||||
Serial.printf("pwm: %d position: %f\n",rc[CH_1].getPwm(),
|
||||
rc[CH_1].getPosition());
|
||||
delay(2000);
|
||||
|
||||
rc[CH_1].setPosition(-50);
|
||||
Serial.printf("\nrc[CH_1].setPosition(-50))\n");
|
||||
Serial.printf("pwm: %d position: %f\n",rc[CH_1].getPwm(),
|
||||
rc[CH_1].getPosition());
|
||||
delay(2000);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue