2011-09-28 21:51:12 -03:00
|
|
|
/*
|
|
|
|
* AP_Guide.h
|
|
|
|
* Copyright (C) James Goppert 2010 <james.goppert@gmail.com>
|
|
|
|
*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#ifndef AP_Guide_H
|
|
|
|
#define AP_Guide_H
|
|
|
|
|
2011-10-16 03:55:34 -03:00
|
|
|
#include <inttypes.h>
|
2011-09-28 21:51:12 -03:00
|
|
|
#include "../GCS_MAVLink/GCS_MAVLink.h"
|
|
|
|
#include "AP_MavlinkCommand.h"
|
2011-10-16 03:55:34 -03:00
|
|
|
#include "../AP_RangeFinder/AP_RangeFinder.h"
|
2011-09-28 21:51:12 -03:00
|
|
|
|
|
|
|
namespace apo {
|
|
|
|
|
2011-10-16 03:55:34 -03:00
|
|
|
class AP_Navigator;
|
|
|
|
class AP_HardwareAbstractionLayer;
|
|
|
|
|
2011-09-28 21:51:12 -03:00
|
|
|
/// Guide class
|
|
|
|
class AP_Guide {
|
|
|
|
public:
|
|
|
|
|
2011-10-26 13:31:11 -03:00
|
|
|
/**
|
|
|
|
* This is the constructor, which requires a link to the navigator.
|
|
|
|
* @param navigator This is the navigator pointer.
|
|
|
|
*/
|
|
|
|
AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal);
|
|
|
|
|
|
|
|
virtual void update() = 0;
|
|
|
|
|
|
|
|
virtual void nextCommand() = 0;
|
|
|
|
|
2011-10-27 20:42:57 -03:00
|
|
|
virtual void updateCommand() {};
|
|
|
|
|
2011-10-26 13:31:11 -03:00
|
|
|
MAV_NAV getMode() const {
|
|
|
|
return _mode;
|
|
|
|
}
|
2011-11-19 22:39:14 -04:00
|
|
|
|
|
|
|
void setMode(MAV_NAV mode) {
|
|
|
|
_mode = mode;
|
|
|
|
}
|
|
|
|
|
2011-10-26 13:31:11 -03:00
|
|
|
uint8_t getCurrentIndex() {
|
|
|
|
return _cmdIndex;
|
|
|
|
}
|
|
|
|
|
|
|
|
void setCurrentIndex(uint8_t val);
|
|
|
|
|
|
|
|
uint8_t getNumberOfCommands() {
|
|
|
|
return _numberOfCommands;
|
|
|
|
}
|
|
|
|
|
|
|
|
void setNumberOfCommands(uint8_t val) {
|
|
|
|
_numberOfCommands.set_and_save(val);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t getPreviousIndex() {
|
|
|
|
// find previous waypoint, TODO, handle non-nav commands
|
|
|
|
int16_t prevIndex = int16_t(getCurrentIndex()) - 1;
|
|
|
|
if (prevIndex < 0)
|
|
|
|
prevIndex = getNumberOfCommands() - 1;
|
|
|
|
return (uint8_t) prevIndex;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t getNextIndex() {
|
|
|
|
// find previous waypoint, TODO, handle non-nav commands
|
|
|
|
int16_t nextIndex = int16_t(getCurrentIndex()) + 1;
|
|
|
|
if (nextIndex > (getNumberOfCommands() - 1))
|
|
|
|
nextIndex = 0;
|
|
|
|
return nextIndex;
|
|
|
|
}
|
|
|
|
|
2011-10-26 14:25:06 -03:00
|
|
|
float getHeadingError();
|
|
|
|
|
2011-10-26 13:31:11 -03:00
|
|
|
float getHeadingCommand() {
|
|
|
|
return _headingCommand;
|
|
|
|
}
|
|
|
|
float getAirSpeedCommand() {
|
|
|
|
return _airSpeedCommand;
|
|
|
|
}
|
|
|
|
float getGroundSpeedCommand() {
|
|
|
|
return _groundSpeedCommand;
|
|
|
|
}
|
|
|
|
float getAltitudeCommand() {
|
|
|
|
return _altitudeCommand;
|
|
|
|
}
|
2011-11-22 17:42:51 -04:00
|
|
|
float getDistanceToNextWaypoint();
|
|
|
|
|
2011-11-20 00:34:14 -04:00
|
|
|
virtual float getPNError() = 0;
|
|
|
|
virtual float getPEError() = 0;
|
|
|
|
virtual float getPDError() = 0;
|
|
|
|
|
2011-10-26 13:31:11 -03:00
|
|
|
MAV_NAV getMode() {
|
|
|
|
return _mode;
|
|
|
|
}
|
|
|
|
uint8_t getCommandIndex() {
|
|
|
|
return _cmdIndex;
|
|
|
|
}
|
2011-09-28 21:51:12 -03:00
|
|
|
|
|
|
|
protected:
|
2011-10-26 13:31:11 -03:00
|
|
|
AP_Navigator * _navigator;
|
|
|
|
AP_HardwareAbstractionLayer * _hal;
|
|
|
|
AP_MavlinkCommand _command, _previousCommand;
|
|
|
|
float _headingCommand;
|
|
|
|
float _airSpeedCommand;
|
|
|
|
float _groundSpeedCommand;
|
|
|
|
float _altitudeCommand;
|
|
|
|
MAV_NAV _mode;
|
|
|
|
AP_Uint8 _numberOfCommands;
|
|
|
|
AP_Uint8 _cmdIndex;
|
|
|
|
uint16_t _nextCommandCalls;
|
|
|
|
uint16_t _nextCommandTimer;
|
2011-09-28 21:51:12 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
class MavlinkGuide: public AP_Guide {
|
|
|
|
public:
|
2011-10-26 13:31:11 -03:00
|
|
|
MavlinkGuide(AP_Navigator * navigator,
|
|
|
|
AP_HardwareAbstractionLayer * hal, float velCmd, float xt, float xtLim);
|
|
|
|
virtual void update();
|
|
|
|
void nextCommand();
|
|
|
|
void handleCommand();
|
2011-10-27 20:42:57 -03:00
|
|
|
void updateCommand();
|
2011-11-20 00:34:14 -04:00
|
|
|
virtual float getPNError();
|
|
|
|
virtual float getPEError();
|
|
|
|
virtual float getPDError();
|
2011-10-06 20:17:49 -03:00
|
|
|
|
2011-09-28 21:51:12 -03:00
|
|
|
private:
|
2011-10-26 13:31:11 -03:00
|
|
|
AP_Var_group _group;
|
|
|
|
AP_Float _velocityCommand;
|
|
|
|
AP_Float _crossTrackGain;
|
|
|
|
AP_Float _crossTrackLim;
|
2011-09-28 21:51:12 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
} // namespace apo
|
|
|
|
|
|
|
|
#endif // AP_Guide_H
|
|
|
|
// vim:ts=4:sw=4:expandtab
|