From 9da193f66ca3fbf0de02f8f84584990c95002cbf Mon Sep 17 00:00:00 2001 From: Jason Kemmerling Date: Mon, 5 Dec 2011 12:32:34 -0500 Subject: [PATCH] Fixed sailboat setup. --- ArduBoat/ControllerSailboat.h | 65 ++++++++--------------------------- 1 file changed, 14 insertions(+), 51 deletions(-) diff --git a/ArduBoat/ControllerSailboat.h b/ArduBoat/ControllerSailboat.h index 2e9b871b14..88b94f99b3 100644 --- a/ArduBoat/ControllerSailboat.h +++ b/ArduBoat/ControllerSailboat.h @@ -16,13 +16,12 @@ class ControllerSailboat: public AP_Controller { public: ControllerSailboat(AP_Navigator * nav, AP_Guide * guide, AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,this,ch_thrust,ch_str,0.1,-0.9,0.9), ch_mode, k_cntrl), + AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,this,ch_sail,ch_str,0.1,-0.9,0.9), ch_mode, k_cntrl), pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, steeringI, steeringD, steeringIMax, steeringYMax), - pidThrust(new AP_Var_group(k_pidThrust, PSTR("THR_")), 1, throttleP, + pidsail(new AP_Var_group(k_pidsail, PSTR("SAIL_")), 1, throttleP, throttleI, throttleD, throttleIMax, throttleYMax, - throttleDFCut), _strCmd(0), _thrustCmd(0), - _rangeFinderFront() + throttleDFCut), _strCmd(0), _sailCmd(0) { _hal->debug->println_P(PSTR("initializing sailboat controller")); @@ -33,61 +32,27 @@ public: new AP_RcChannel(k_chStr, PSTR("STR_"), hal->radio, 3, 1100, 1500, 1900, RC_MODE_INOUT, false)); _hal->rc.push_back( - new AP_RcChannel(k_chThrust, PSTR("THR_"), hal->radio, 2, 1100, 1500, + new AP_RcChannel(k_chsail, PSTR("SAIL_"), hal->radio, 2, 1100, 1500, 1900, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chFwdRev, PSTR("FWDREV_"), hal->radio, 4, 1100, 1500, - 1900, RC_MODE_IN, false)); - - for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) { - RangeFinder * rF = _hal->rangeFinders[i]; - if (rF == NULL) - continue; - if (rF->orientation_x == 1 && rF->orientation_y == 0 - && rF->orientation_z == 0) - _rangeFinderFront = rF; - } } private: // methods void manualLoop(const float dt) { _strCmd = _hal->rc[ch_str]->getRadioPosition(); - _thrustCmd = _hal->rc[ch_thrust]->getRadioPosition(); - if (useForwardReverseSwitch && _hal->rc[ch_FwdRev]->getRadioPosition() < 0.0) - _thrustCmd = -_thrustCmd; + _sailCmd = _hal->rc[ch_sail]->getRadioPosition(); } void autoLoop(const float dt) { - //_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_thrust]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition()); + //_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_sail]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition()); // neglects heading command derivative float steering = pidStr.update(_guide->getHeadingError(), -_nav->getYawRate(), dt); - float thrust = pidThrust.update( - _guide->getGroundSpeedCommand() - - _nav->getGroundSpeed(), dt); - - // obstacle avoidance overrides - // try to drive around the obstacle in front. if this fails, stop - if (_rangeFinderFront) { - _rangeFinderFront->read(); - - int distanceToObstacle = _rangeFinderFront->distance; - if (distanceToObstacle < 100) { - thrust = 0; // Avoidance didn't work out. Stopping - } - else if (distanceToObstacle < 650) { - // Deviating from the course. Deviation angle is inverse proportional - // to the distance to the obstacle, with 15 degrees min angle, 180 - max - steering += (15 + 165 * - (1 - ((float)(distanceToObstacle - 100)) / 550)) * deg2Rad; - } - } - + float sail = 0; _strCmd = steering; - _thrustCmd = thrust; + _sailCmd = sail; } void setMotors() { _hal->rc[ch_str]->setPosition(_strCmd); - _hal->rc[ch_thrust]->setPosition(fabs(_thrustCmd) < 0.1 ? 0 : _thrustCmd); + _hal->rc[ch_sail]->setPosition(fabs(_sailCmd) < 0.1 ? 0 : _sailCmd); } void handleFailsafe() { // turn off @@ -96,19 +61,17 @@ private: // attributes enum { - ch_mode = 0, ch_str, ch_thrust, ch_FwdRev + ch_mode = 0, ch_str, ch_sail }; enum { - k_chMode = k_radioChannelsStart, k_chStr, k_chThrust, k_chFwdRev + k_chMode = k_radioChannelsStart, k_chStr, k_chsail }; enum { - k_pidStr = k_controllersStart, k_pidThrust + k_pidStr = k_controllersStart, k_pidsail }; BlockPIDDfb pidStr; - BlockPID pidThrust; - float _strCmd, _thrustCmd; - - RangeFinder * _rangeFinderFront; + BlockPID pidsail; + float _strCmd, _sailCmd; }; } // namespace apo