Sailboat wind measurement working.

This commit is contained in:
Jason Kemmerling 2011-12-05 15:53:29 -05:00
parent 9da193f66c
commit 1d9efea9af
4 changed files with 10 additions and 7 deletions

View File

@ -41,7 +41,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD
// compass orientation: See AP_Compass_HMC5843.h for possible values
// battery monitoring
static const bool batteryMonitorEnabled = true;
static const bool batteryMonitorEnabled = false;
static const uint8_t batteryPin = 0;
static const float batteryVoltageDivRatio = 6;
static const float batteryMinVolt = 10.0;

View File

@ -44,6 +44,8 @@ private:
}
void autoLoop(const float dt) {
//_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_sail]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition());
float windDir = analogRead(1);
_hal->debug->printf_P(PSTR("wind directiono: %f\n"),windDir);
// neglects heading command derivative
float steering = pidStr.update(_guide->getHeadingError(), -_nav->getYawRate(), dt);
float sail = 0;

View File

@ -41,7 +41,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD
// compass orientation: See AP_Compass_HMC5843.h for possible values
// battery monitoring
static const bool batteryMonitorEnabled = true;
static const bool batteryMonitorEnabled = false;
static const uint8_t batteryPin = 0;
static const float batteryVoltageDivRatio = 6;
static const float batteryMinVolt = 10.0;

View File

@ -47,16 +47,17 @@ void setup() {
hal->scheduler = new AP_TimerProcess;
hal->scheduler->init(hal->isr_registry);
// initialize the adc
hal->debug->println_P(PSTR("initializing adc"));
hal->adc = new ADC_CLASS;
hal->adc->Init(hal->scheduler);
/*
* Sensor initialization
*/
if (hal->getMode() == MODE_LIVE) {
hal->debug->println_P(PSTR("initializing adc"));
hal->adc = new ADC_CLASS;
hal->adc->Init(hal->scheduler);
if (batteryMonitorEnabled) {
hal->batteryMonitor = new AP_BatteryMonitor(batteryPin,batteryVoltageDivRatio,batteryMinVolt,batteryMaxVolt);
}