mirror of https://github.com/ArduPilot/ardupilot
AP_RcChannel demos updated for AP_Var.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1632 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6728355889
commit
253307e2f0
|
@ -14,7 +14,7 @@
|
||||||
#include "AP_RcChannel.h"
|
#include "AP_RcChannel.h"
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
|
||||||
AP_RcChannel::AP_RcChannel(AP_Var::Key & key, const prog_char * name, APM_RC_Class & rc, const uint8_t & ch,
|
AP_RcChannel::AP_RcChannel(AP_Var::Key key, const prog_char * name, APM_RC_Class & rc, const uint8_t & ch,
|
||||||
const float & scale, const float & center,
|
const float & scale, const float & center,
|
||||||
const uint16_t & pwmMin,
|
const uint16_t & pwmMin,
|
||||||
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
|
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
|
||||||
|
@ -23,8 +23,8 @@ AP_RcChannel::AP_RcChannel(AP_Var::Key & key, const prog_char * name, APM_RC_Cla
|
||||||
AP_Var_group(key,name),
|
AP_Var_group(key,name),
|
||||||
_rc(rc),
|
_rc(rc),
|
||||||
ch(this,0,ch,PSTR("CH")),
|
ch(this,0,ch,PSTR("CH")),
|
||||||
scale(this,1,ch,PSTR("SCALE")),
|
scale(this,1,scale,PSTR("SCALE")),
|
||||||
center(this,2,ch,PSTR("CENTER")),
|
center(this,2,center,PSTR("CENTER")),
|
||||||
pwmMin(this,3,pwmMin,PSTR("PMIN")),
|
pwmMin(this,3,pwmMin,PSTR("PMIN")),
|
||||||
pwmMax(this,4,pwmMax,PSTR("PMAX")),
|
pwmMax(this,4,pwmMax,PSTR("PMAX")),
|
||||||
pwmNeutral(this,5,pwmNeutral,PSTR("PNTRL")),
|
pwmNeutral(this,5,pwmNeutral,PSTR("PNTRL")),
|
||||||
|
|
|
@ -18,7 +18,7 @@ class AP_RcChannel : public AP_Var_group {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
AP_RcChannel(AP_Var::Key & key, const prog_char * name, APM_RC_Class & rc, const uint8_t & ch,
|
AP_RcChannel(AP_Var::Key key, const prog_char * name, APM_RC_Class & rc, const uint8_t & ch,
|
||||||
const float & scale=45.0, const float & center=0.0,
|
const float & scale=45.0, const float & center=0.0,
|
||||||
const uint16_t & pwmMin=1200,
|
const uint16_t & pwmMin=1200,
|
||||||
const uint16_t & pwmNeutral=1500, const uint16_t & pwmMax=1800,
|
const uint16_t & pwmNeutral=1500, const uint16_t & pwmMax=1800,
|
||||||
|
@ -47,7 +47,6 @@ public:
|
||||||
uint16_t getPwm() { return _pwm; }
|
uint16_t getPwm() { return _pwm; }
|
||||||
float getPosition() { return _pwmToPosition(_pwm); }
|
float getPosition() { return _pwmToPosition(_pwm); }
|
||||||
float getNormalized() { return getPosition()/scale; }
|
float getNormalized() { return getPosition()/scale; }
|
||||||
const char * getName() { return _name; }
|
|
||||||
|
|
||||||
// did our read come in 50µs below the min?
|
// did our read come in 50µs below the min?
|
||||||
bool failSafe() { _pwm < (pwmMin - 50); }
|
bool failSafe() { _pwm < (pwmMin - 50); }
|
||||||
|
|
|
@ -9,61 +9,86 @@
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||||
#include <APM_RC.h>
|
#include <APM_RC.h>
|
||||||
|
#include <AP_Vector.h>
|
||||||
|
|
||||||
FastSerialPort0(Serial); // make sure this procees variable declarations
|
FastSerialPort0(Serial); // make sure this proceeds variable declarations
|
||||||
|
|
||||||
// test settings
|
// test settings
|
||||||
uint8_t nChannels = 8;
|
|
||||||
|
|
||||||
// channel configuration
|
class RadioTest
|
||||||
AP_RcChannel rcCh[] =
|
|
||||||
{
|
{
|
||||||
AP_RcChannel("ROLL",APM_RC,0,45),
|
private:
|
||||||
AP_RcChannel("PITCH",APM_RC,1,45),
|
float testPosition;
|
||||||
AP_RcChannel("THR",APM_RC,2,100),
|
int8_t testSign;
|
||||||
AP_RcChannel("YAW",APM_RC,3,45),
|
enum
|
||||||
AP_RcChannel("CH5",APM_RC,4,1),
|
{
|
||||||
AP_RcChannel("CH6",APM_RC,5,1),
|
version,
|
||||||
AP_RcChannel("CH7",APM_RC,6,1),
|
rollKey,
|
||||||
AP_RcChannel("CH8",APM_RC,7,1)
|
pitchKey,
|
||||||
|
thrKey,
|
||||||
|
yawKey,
|
||||||
|
ch5Key,
|
||||||
|
ch6Key,
|
||||||
|
ch7Key,
|
||||||
|
ch8Key
|
||||||
};
|
};
|
||||||
|
Vector<AP_RcChannel *> ch;
|
||||||
// test position
|
public:
|
||||||
float testPosition = 2;
|
RadioTest() : testPosition(2), testSign(1)
|
||||||
int8_t testSign = 1;
|
|
||||||
|
|
||||||
void setup()
|
|
||||||
{
|
{
|
||||||
|
ch.push_back(new AP_RcChannel(rollKey,PSTR("ROLL"),APM_RC,1,45));
|
||||||
|
ch.push_back(new AP_RcChannel(pitchKey,PSTR("PITCH"),APM_RC,2,45));
|
||||||
|
ch.push_back(new AP_RcChannel(thrKey,PSTR("THR"),APM_RC,3,100));
|
||||||
|
ch.push_back(new AP_RcChannel(yawKey,PSTR("YAW"),APM_RC,4,45));
|
||||||
|
ch.push_back(new AP_RcChannel(ch5Key,PSTR("CH5"),APM_RC,5,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch6Key,PSTR("CH6"),APM_RC,6,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch7Key,PSTR("CH7"),APM_RC,7,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch8Key,PSTR("CH8"),APM_RC,8,1));
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
delay(2000);
|
delay(2000);
|
||||||
|
|
||||||
Serial.println("ArduPilot RC Channel test");
|
Serial.println("ArduPilot RC Channel test");
|
||||||
|
|
||||||
APM_RC.Init(); // APM Radio initialization
|
APM_RC.Init(); // APM Radio initialization
|
||||||
|
|
||||||
delay(2000);
|
delay(2000);
|
||||||
//eepromRegistry.print(Serial); // show eeprom map
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void update()
|
||||||
{
|
{
|
||||||
// read the radio
|
// read the radio
|
||||||
for (int i=0;i<nChannels;i++) rcCh[i].readRadio();
|
for (int i=0;i<ch.getSize();i++) ch[i]->readRadio();
|
||||||
|
|
||||||
// print channel names
|
// print channel names
|
||||||
Serial.print("\n\t\t");
|
Serial.print("\t\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7s\t",rcCh[i].getName());
|
static char name[7];
|
||||||
|
for (int i=0;i<ch.getSize();i++)
|
||||||
|
{
|
||||||
|
ch[i]->copy_name(name,7);
|
||||||
|
Serial.printf("%7s\t",name);
|
||||||
|
}
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
// print pwm
|
// print pwm
|
||||||
Serial.printf("pwm :\t");
|
Serial.printf("pwm :\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7d\t",rcCh[i].getPwm());
|
for (int i=0;i<ch.getSize();i++) Serial.printf("%7d\t",ch[i]->getPwm());
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
// print position
|
// print position
|
||||||
Serial.printf("position :\t");
|
Serial.printf("position :\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7.2f\t",rcCh[i].getPosition());
|
for (int i=0;i<ch.getSize();i++) Serial.printf("%7.2f\t",ch[i]->getPosition());
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
delay(500);
|
delay(500);
|
||||||
}
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
RadioTest * test;
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
test = new RadioTest;
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
test->update();
|
||||||
|
}
|
||||||
|
|
|
@ -9,42 +9,50 @@
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||||
#include <APM_RC.h>
|
#include <APM_RC.h>
|
||||||
|
#include <AP_Vector.h>
|
||||||
|
|
||||||
FastSerialPort0(Serial); // make sure this procees variable declarations
|
FastSerialPort0(Serial); // make sure this proceeds variable declarations
|
||||||
|
|
||||||
// test settings
|
// test settings
|
||||||
uint8_t nChannels = 8;
|
|
||||||
|
|
||||||
// channel configuration
|
class RadioTest
|
||||||
AP_RcChannel rcCh[] =
|
|
||||||
{
|
{
|
||||||
AP_RcChannel("ROLL",APM_RC,0,45),
|
private:
|
||||||
AP_RcChannel("PITCH",APM_RC,1,45),
|
float testPosition;
|
||||||
AP_RcChannel("THR",APM_RC,2,100),
|
int8_t testSign;
|
||||||
AP_RcChannel("YAW",APM_RC,3,45),
|
enum
|
||||||
AP_RcChannel("CH5",APM_RC,4,1),
|
{
|
||||||
AP_RcChannel("CH6",APM_RC,5,1),
|
version,
|
||||||
AP_RcChannel("CH7",APM_RC,6,1),
|
rollKey,
|
||||||
AP_RcChannel("CH8",APM_RC,7,1)
|
pitchKey,
|
||||||
|
thrKey,
|
||||||
|
yawKey,
|
||||||
|
ch5Key,
|
||||||
|
ch6Key,
|
||||||
|
ch7Key,
|
||||||
|
ch8Key
|
||||||
};
|
};
|
||||||
|
Vector<AP_RcChannel *> ch;
|
||||||
// test position
|
public:
|
||||||
float testPosition = 2;
|
RadioTest() : testPosition(2), testSign(1)
|
||||||
int8_t testSign = 1;
|
|
||||||
|
|
||||||
void setup()
|
|
||||||
{
|
{
|
||||||
|
ch.push_back(new AP_RcChannel(rollKey,PSTR("ROLL"),APM_RC,1,45));
|
||||||
|
ch.push_back(new AP_RcChannel(pitchKey,PSTR("PITCH"),APM_RC,2,45));
|
||||||
|
ch.push_back(new AP_RcChannel(thrKey,PSTR("THR"),APM_RC,3,100));
|
||||||
|
ch.push_back(new AP_RcChannel(yawKey,PSTR("YAW"),APM_RC,4,45));
|
||||||
|
ch.push_back(new AP_RcChannel(ch5Key,PSTR("CH5"),APM_RC,5,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch6Key,PSTR("CH6"),APM_RC,6,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch7Key,PSTR("CH7"),APM_RC,7,1));
|
||||||
|
ch.push_back(new AP_RcChannel(ch8Key,PSTR("CH8"),APM_RC,8,1));
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
delay(2000);
|
delay(2000);
|
||||||
|
|
||||||
Serial.println("ArduPilot RC Channel test");
|
Serial.println("ArduPilot RC Channel test");
|
||||||
|
|
||||||
APM_RC.Init(); // APM Radio initialization
|
APM_RC.Init(); // APM Radio initialization
|
||||||
|
|
||||||
delay(2000);
|
delay(2000);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void update()
|
||||||
{
|
{
|
||||||
// update test value
|
// update test value
|
||||||
testPosition += testSign*.1;
|
testPosition += testSign*.1;
|
||||||
|
@ -61,25 +69,43 @@ void loop()
|
||||||
}
|
}
|
||||||
|
|
||||||
// set channel positions
|
// set channel positions
|
||||||
for (int i=0;i<nChannels;i++) rcCh[i].setNormalized(testPosition);
|
for (int i=0;i<ch.getSize();i++) ch[i]->setNormalized(testPosition);
|
||||||
|
|
||||||
// print test position
|
// print test position
|
||||||
Serial.printf("\nnormalized position (%f)\n",testPosition);
|
Serial.printf("\nnormalized position (%f)\n",testPosition);
|
||||||
|
|
||||||
// print channel names
|
// print channel names
|
||||||
Serial.print("\t\t");
|
Serial.print("\t\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7s\t",rcCh[i].getName());
|
static char name[7];
|
||||||
|
for (int i=0;i<ch.getSize();i++)
|
||||||
|
{
|
||||||
|
ch[i]->copy_name(name,7);
|
||||||
|
Serial.printf("%7s\t",name);
|
||||||
|
}
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
// print pwm
|
// print pwm
|
||||||
Serial.printf("pwm :\t");
|
Serial.printf("pwm :\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7d\t",rcCh[i].getPwm());
|
for (int i=0;i<ch.getSize();i++) Serial.printf("%7d\t",ch[i]->getPwm());
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
// print position
|
// print position
|
||||||
Serial.printf("position :\t");
|
Serial.printf("position :\t");
|
||||||
for (int i=0;i<nChannels;i++) Serial.printf("%7.2f\t",rcCh[i].getPosition());
|
for (int i=0;i<ch.getSize();i++) Serial.printf("%7.2f\t",ch[i]->getPosition());
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
|
||||||
delay(500);
|
delay(500);
|
||||||
}
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
RadioTest * test;
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
test = new RadioTest;
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
test->update();
|
||||||
|
}
|
||||||
|
|
Loading…
Reference in New Issue