mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Updated RcChannel examples.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1372 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b3089a9c73
commit
d7c6bc7c16
@ -15,90 +15,56 @@ FastSerialPort0(Serial); // make sure this procees variable declarations
|
||||
|
||||
// test settings
|
||||
uint8_t nChannels = 8;
|
||||
bool loadEEProm = false;
|
||||
bool saveEEProm = false;
|
||||
|
||||
// channel configuration
|
||||
Vector< AP_EEPromVar<float> * > scale;
|
||||
Vector< AP_EEPromVar<uint16_t> * > pwmMin;
|
||||
Vector< AP_EEPromVar<uint16_t> * > pwmNeutral;
|
||||
Vector< AP_EEPromVar<uint16_t> * > pwmMax;
|
||||
Vector< AP_EEPromVar<uint16_t> * > pwmDeadZone;
|
||||
Vector< AP_Var<bool> * > filter;
|
||||
Vector< AP_Var<bool> * > reverse;
|
||||
Vector< AP_RcChannel * > rc;
|
||||
AP_RcChannel rcCh[] =
|
||||
{
|
||||
AP_RcChannel("ROLL",APM_RC,0,100.0),
|
||||
AP_RcChannel("PITCH",APM_RC,1,45),
|
||||
AP_RcChannel("THR",APM_RC,2,100),
|
||||
AP_RcChannel("YAW",APM_RC,3,45),
|
||||
AP_RcChannel("CH5",APM_RC,4,1),
|
||||
AP_RcChannel("CH6",APM_RC,5,1),
|
||||
AP_RcChannel("CH7",APM_RC,6,1),
|
||||
AP_RcChannel("CH8",APM_RC,7,1)
|
||||
};
|
||||
|
||||
// test position
|
||||
float testPosition = 2;
|
||||
int8_t testSign = 1;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
delay(2000);
|
||||
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
// add channels
|
||||
for (int i=0;i<nChannels;i++)
|
||||
{
|
||||
char num[5];
|
||||
itoa(i+1,num,10);
|
||||
|
||||
Serial.printf("\nInitializing channel %d", i+1);
|
||||
|
||||
// initialize eeprom settings
|
||||
scale.push_back(new AP_EEPromVar<float>(1.0,strcat("SCALE",num)));
|
||||
pwmMin.push_back(new AP_EEPromVar<uint16_t>(1200,strcat("PWM_MIN",num)));
|
||||
pwmNeutral.push_back(new AP_EEPromVar<uint16_t>(1500,strcat("PWM_NEUTRAL",num)));
|
||||
pwmMax.push_back(new AP_EEPromVar<uint16_t>(1800,strcat("PWM_MAX",num)));
|
||||
pwmDeadZone.push_back(new AP_EEPromVar<uint16_t>(10,strcat("PWM_DEADZONE",num)));
|
||||
filter.push_back(new AP_EEPromVar<bool>(false,strcat("FILTER",num)));
|
||||
reverse.push_back(new AP_EEPromVar<bool>(false,strcat("REVERSE",num)));
|
||||
|
||||
// save
|
||||
if (saveEEProm)
|
||||
{
|
||||
scale[i]->save();
|
||||
pwmMin[i]->save();
|
||||
pwmNeutral[i]->save();
|
||||
pwmMax[i]->save();
|
||||
pwmDeadZone[i]->save();
|
||||
filter[i]->save();
|
||||
reverse[i]->save();
|
||||
}
|
||||
|
||||
// load
|
||||
if (loadEEProm)
|
||||
{
|
||||
scale[i]->load();
|
||||
pwmMin[i]->load();
|
||||
pwmNeutral[i]->load();
|
||||
pwmMax[i]->load();
|
||||
pwmDeadZone[i]->load();
|
||||
filter[i]->load();
|
||||
reverse[i]->load();
|
||||
}
|
||||
|
||||
// find neutral position
|
||||
AP_RcChannel * ch = new AP_RcChannel(APM_RC,i,scale[i]->get(),
|
||||
pwmMin[i]->get(),pwmNeutral[i]->get(),pwmMax[i]->get(),
|
||||
pwmDeadZone[i]->get(),filter[i]->get(),reverse[i]->get());
|
||||
|
||||
ch->readRadio();
|
||||
pwmNeutral[i]->set(ch->getPwm());
|
||||
|
||||
// add rc channel
|
||||
rc.push_back(ch);
|
||||
}
|
||||
delay(2000);
|
||||
eepromRegistry.print(Serial); // show eeprom map
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// read radio
|
||||
for (int i=0;i<nChannels;i++) rc[i]->readRadio();
|
||||
|
||||
// read test positions
|
||||
Serial.printf("\npwm :\t");
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7d\t",rc[i]->getPwm());
|
||||
// read the radio
|
||||
for (int i=0;i<nChannels;i++) rcCh[i].readRadio();
|
||||
|
||||
// print channel names
|
||||
Serial.print("\n\t\t");
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7s\t",rcCh[i].getName());
|
||||
Serial.println();
|
||||
|
||||
// print pwm
|
||||
Serial.printf("pwm :\t");
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7d\t",rcCh[i].getPwm());
|
||||
Serial.println();
|
||||
|
||||
// print position
|
||||
Serial.printf("position :\t");
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7.2f\t",rc[i]->getPosition());
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7.2f\t",rcCh[i].getPosition());
|
||||
Serial.println();
|
||||
delay(100);
|
||||
|
||||
delay(500);
|
||||
}
|
||||
|
@ -5,7 +5,6 @@
|
||||
|
||||
*/
|
||||
|
||||
#define AP_DISPLAYMEM
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||
@ -31,28 +30,45 @@ AP_RcChannel rcCh[] =
|
||||
};
|
||||
|
||||
// test position
|
||||
float testPosition = 0;
|
||||
float testPosition = 2;
|
||||
int8_t testSign = 1;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
delay(2000);
|
||||
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
eepromRegistry.print(Serial); // show eeprom map
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// update test value
|
||||
testPosition += testSign*.1;
|
||||
if (testPosition > 1)
|
||||
{
|
||||
eepromRegistry.print(Serial); // show eeprom map
|
||||
testPosition = 1;
|
||||
testSign = -1;
|
||||
}
|
||||
else if (testPosition < -1)
|
||||
{
|
||||
testPosition = -1;
|
||||
testSign = 1;
|
||||
}
|
||||
|
||||
// set channel positions
|
||||
for (int i=0;i<nChannels;i++) rcCh[i].setNormalized(testPosition);
|
||||
|
||||
// print test position
|
||||
Serial.printf("\ntestPosition (%f)\n\t\t",testPosition);
|
||||
Serial.printf("\nnormalized position (%f)\n",testPosition);
|
||||
|
||||
// print channgel names
|
||||
// print channel names
|
||||
Serial.print("\t\t");
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7s\t",rcCh[i].getName());
|
||||
Serial.println();
|
||||
|
||||
@ -66,18 +82,5 @@ void loop()
|
||||
for (int i=0;i<nChannels;i++) Serial.printf("%7.2f\t",rcCh[i].getPosition());
|
||||
Serial.println();
|
||||
|
||||
// update test value
|
||||
testPosition += testSign*.05;
|
||||
if (testPosition > 1)
|
||||
{
|
||||
testPosition = 1;
|
||||
testSign = -1;
|
||||
}
|
||||
else if (testPosition < -1)
|
||||
{
|
||||
testPosition = -1;
|
||||
testSign = 1;
|
||||
}
|
||||
|
||||
delay(100);
|
||||
delay(500);
|
||||
}
|
||||
|
@ -1,84 +0,0 @@
|
||||
/*
|
||||
Example of RC_Channel library.
|
||||
Code by James Goppert/ Jason Short. 2010
|
||||
DIYDrones.com
|
||||
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||
#include <AP_EEProm.h>
|
||||
#include <APM_RC.h>
|
||||
|
||||
FastSerialPort0(Serial); // make sure this proceed variable declarations
|
||||
|
||||
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(false,"RC1_FILTER");
|
||||
AP_Var<bool> reverse(false,"RC1_REVERSE");
|
||||
|
||||
float testPosition = 0;
|
||||
uint16_t testPwm = 1500;
|
||||
|
||||
AP_RcChannel rc[] =
|
||||
{
|
||||
AP_RcChannel(APM_RC,CH_1,scale.get(),pwmMin.get(),pwmNeutral.get(),pwmMax.get(),
|
||||
pwmDeadZone.get(),filter.get(),reverse.get())
|
||||
|
||||
};
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
delay(1000);
|
||||
|
||||
// configuratoin
|
||||
scale.set(100);
|
||||
Serial.printf("\nscale.set(100)\n");
|
||||
delay(2000);
|
||||
|
||||
// find neutral radio position
|
||||
rc[CH_1].readRadio();
|
||||
Serial.printf("\nrc[CH_1].readRadio()\n");
|
||||
Serial.printf("\npwmNeutral.set(rc[CH_1].getPwm())\n");
|
||||
pwmNeutral.set(rc[CH_1].getPwm());
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// get the min pwm
|
||||
Serial.printf("\npwmMin.get(): %d\n", pwmMin.get());
|
||||
delay(2000);
|
||||
|
||||
// set by pwm
|
||||
rc[CH_1].setPwm(testPwm);
|
||||
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);
|
||||
|
||||
// set by position
|
||||
rc[CH_1].setPosition(testPosition);
|
||||
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);
|
||||
|
||||
// update test value
|
||||
testPosition += 10;
|
||||
if (testPosition > 100) testPosition = -100;
|
||||
testPwm += 100;
|
||||
if (testPwm > 1800) testPosition = 1200;
|
||||
}
|
Loading…
Reference in New Issue
Block a user