mirror of https://github.com/ArduPilot/ardupilot
ArduRover: latest rover code is in APMRover2 directory
This commit is contained in:
parent
4e7e78d091
commit
9edda1407a
|
@ -1,25 +0,0 @@
|
||||||
// Libraries
|
|
||||||
#include <Wire.h>
|
|
||||||
#include <FastSerial.h>
|
|
||||||
#include <AP_Common.h>
|
|
||||||
#include <APM_RC.h>
|
|
||||||
#include <AP_RangeFinder.h>
|
|
||||||
#include <GCS_MAVLink.h>
|
|
||||||
#include <AP_ADC.h>
|
|
||||||
#include <AP_DCM.h>
|
|
||||||
#include <AP_Compass.h>
|
|
||||||
#include <Wire.h>
|
|
||||||
#include <AP_GPS.h>
|
|
||||||
#include <AP_IMU.h>
|
|
||||||
#include <APM_BMP085.h>
|
|
||||||
#include <ModeFilter.h>
|
|
||||||
#include <APO.h>
|
|
||||||
#include <AP_AnalogSource.h>
|
|
||||||
#include <AP_InertialSensor.h>
|
|
||||||
|
|
||||||
// Vehicle Configuration
|
|
||||||
#include "CarStampede.h"
|
|
||||||
//#include "TankGeneric.h"
|
|
||||||
|
|
||||||
// ArduPilotOne Default Setup
|
|
||||||
#include "APO_DefaultSetup.h"
|
|
|
@ -1,62 +0,0 @@
|
||||||
/*
|
|
||||||
* CarStampede.h
|
|
||||||
*
|
|
||||||
* Created on: May 1, 2011
|
|
||||||
* Author: jgoppert
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef CARSTAMPEDE_H_
|
|
||||||
#define CARSTAMPEDE_H_
|
|
||||||
|
|
||||||
// vehicle options
|
|
||||||
using namespace apo;
|
|
||||||
static const AP_Board::options_t options = AP_Board::opt_gps | AP_Board::opt_baro | AP_Board::opt_compass;
|
|
||||||
static const MAV_TYPE vehicle = UGV_GROUND_ROVER;
|
|
||||||
//static const apo::AP_Board::mode_e boardMode = apo::AP_Board::MODE_HIL_CNTL;
|
|
||||||
static const apo::AP_Board::mode_e boardMode = apo::AP_Board::MODE_LIVE;
|
|
||||||
static const uint8_t heartBeatTimeout = 3;
|
|
||||||
|
|
||||||
// algorithm selection
|
|
||||||
#define CONTROLLER_CLASS ControllerCar
|
|
||||||
#define GUIDE_CLASS MavlinkGuide
|
|
||||||
#define NAVIGATOR_CLASS Navigator_Dcm
|
|
||||||
|
|
||||||
// hardware selection
|
|
||||||
//#define BOARD_TYPE Board_APM1
|
|
||||||
//#define BOARD_TYPE Board_APM1_2560
|
|
||||||
#define BOARD_TYPE Board_APM2
|
|
||||||
|
|
||||||
static const bool useForwardReverseSwitch = false;
|
|
||||||
|
|
||||||
// loop rates
|
|
||||||
static const float loopRate = 150; // attitude nav
|
|
||||||
static const float loop0Rate = 50; // controller
|
|
||||||
static const float loop1Rate = 5; // pos nav/ gcs fast
|
|
||||||
static const float loop2Rate = 1; // gcs slow
|
|
||||||
static const float loop3Rate = 0.1;
|
|
||||||
|
|
||||||
// gains
|
|
||||||
static const float steeringP = 0.1;
|
|
||||||
static const float steeringI = 0.0;
|
|
||||||
static const float steeringD = 0.1;
|
|
||||||
static const float steeringIMax = 0.0;
|
|
||||||
static const float steeringYMax = 1;
|
|
||||||
static const float steeringDFCut = 25.0;
|
|
||||||
|
|
||||||
static const float throttleP = 0.1;
|
|
||||||
static const float throttleI = 0.0;
|
|
||||||
static const float throttleD = 0.0;
|
|
||||||
static const float throttleIMax = 0.0;
|
|
||||||
static const float throttleYMax = 1;
|
|
||||||
static const float throttleDFCut = 0.0;
|
|
||||||
|
|
||||||
// guidance
|
|
||||||
static const float velCmd = 5;
|
|
||||||
static const float xt = 10;
|
|
||||||
static const float xtLim = 90;
|
|
||||||
|
|
||||||
#include "ControllerCar.h"
|
|
||||||
|
|
||||||
#endif /* CARSTAMPEDE_H_ */
|
|
||||||
// vim:ts=4:sw=4:expandtab
|
|
|
@ -1,117 +0,0 @@
|
||||||
/*
|
|
||||||
* ControllerCar.h
|
|
||||||
*
|
|
||||||
* Created on: Jun 30, 2011
|
|
||||||
* Author: jgoppert
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef CONTROLLERCAR_H_
|
|
||||||
#define CONTROLLERCAR_H_
|
|
||||||
|
|
||||||
#include "../APO/AP_Controller.h"
|
|
||||||
|
|
||||||
namespace apo {
|
|
||||||
|
|
||||||
class ControllerCar: public AP_Controller {
|
|
||||||
public:
|
|
||||||
ControllerCar(AP_Navigator * nav, AP_Guide * guide,
|
|
||||||
AP_Board * board) :
|
|
||||||
AP_Controller(nav, guide, board,new AP_ArmingMechanism(board,this,ch_thrust,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,
|
|
||||||
throttleI, throttleD, throttleIMax, throttleYMax,
|
|
||||||
throttleDFCut), _strCmd(0), _thrustCmd(0),
|
|
||||||
_rangeFinderFront()
|
|
||||||
{
|
|
||||||
_board->debug->println_P(PSTR("initializing car controller"));
|
|
||||||
|
|
||||||
_board->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chMode, PSTR("MODE_"), board->radio, 5, 1100,
|
|
||||||
1500, 1900, RC_MODE_IN, false));
|
|
||||||
_board->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chStr, PSTR("STR_"), board->radio, 3, 1100, 1500,
|
|
||||||
1900, RC_MODE_INOUT, false));
|
|
||||||
_board->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chThrust, PSTR("THR_"), board->radio, 2, 1100, 1500,
|
|
||||||
1900, RC_MODE_INOUT, false));
|
|
||||||
_board->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chFwdRev, PSTR("FWDREV_"), board->radio, 4, 1100, 1500,
|
|
||||||
1900, RC_MODE_IN, false));
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < _board->rangeFinders.getSize(); i++) {
|
|
||||||
RangeFinder * rF = _board->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 = _board->rc[ch_str]->getRadioPosition();
|
|
||||||
_thrustCmd = _board->rc[ch_thrust]->getRadioPosition();
|
|
||||||
if (useForwardReverseSwitch && _board->rc[ch_FwdRev]->getRadioPosition() < 0.0)
|
|
||||||
_thrustCmd = -_thrustCmd;
|
|
||||||
}
|
|
||||||
void autoLoop(const float dt) {
|
|
||||||
//_board->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_board->rc[ch_thrust]->getRadioPosition(), _board->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;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
_strCmd = steering;
|
|
||||||
_thrustCmd = thrust;
|
|
||||||
}
|
|
||||||
void setMotors() {
|
|
||||||
_board->rc[ch_str]->setPosition(_strCmd);
|
|
||||||
_board->rc[ch_thrust]->setPosition(fabs(_thrustCmd) < 0.1 ? 0 : _thrustCmd);
|
|
||||||
}
|
|
||||||
void handleFailsafe() {
|
|
||||||
// turn off
|
|
||||||
setMode(MAV_MODE_LOCKED);
|
|
||||||
}
|
|
||||||
|
|
||||||
// attributes
|
|
||||||
enum {
|
|
||||||
ch_mode = 0, ch_str, ch_thrust, ch_FwdRev
|
|
||||||
};
|
|
||||||
enum {
|
|
||||||
k_chMode = k_radioChannelsStart, k_chStr, k_chThrust, k_chFwdRev
|
|
||||||
};
|
|
||||||
enum {
|
|
||||||
k_pidStr = k_controllersStart, k_pidThrust
|
|
||||||
};
|
|
||||||
BlockPIDDfb pidStr;
|
|
||||||
BlockPID pidThrust;
|
|
||||||
float _strCmd, _thrustCmd;
|
|
||||||
|
|
||||||
RangeFinder * _rangeFinderFront;
|
|
||||||
};
|
|
||||||
|
|
||||||
} // namespace apo
|
|
||||||
|
|
||||||
#endif /* CONTROLLERCAR_H_ */
|
|
||||||
// vim:ts=4:sw=4:expandtab
|
|
|
@ -1,91 +0,0 @@
|
||||||
/*
|
|
||||||
* ControllerTank.h
|
|
||||||
*
|
|
||||||
* Created on: Jun 30, 2011
|
|
||||||
* Author: jgoppert
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef CONTROLLERTANK_H_
|
|
||||||
#define CONTROLLERTANK_H_
|
|
||||||
|
|
||||||
#include "../APO/AP_Controller.h"
|
|
||||||
|
|
||||||
namespace apo {
|
|
||||||
|
|
||||||
class ControllerTank: public AP_Controller {
|
|
||||||
public:
|
|
||||||
ControllerTank(AP_Navigator * nav, AP_Guide * guide,
|
|
||||||
AP_HardwareAbstractionLayer * hal) :
|
|
||||||
AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,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),
|
|
||||||
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
|
|
||||||
throttleI, throttleD, throttleIMax, throttleYMax,
|
|
||||||
throttleDFCut), _headingOutput(0), _throttleOutput(0) {
|
|
||||||
_hal->debug->println_P(PSTR("initializing tank controller"));
|
|
||||||
|
|
||||||
_hal->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
|
|
||||||
1500, 1900, RC_MODE_IN, false));
|
|
||||||
_hal->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500,
|
|
||||||
1900, RC_MODE_OUT, false));
|
|
||||||
_hal->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500,
|
|
||||||
1900, RC_MODE_OUT, false));
|
|
||||||
_hal->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500,
|
|
||||||
1900, RC_MODE_IN, false));
|
|
||||||
_hal->rc.push_back(
|
|
||||||
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
|
|
||||||
1900, RC_MODE_IN, false));
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
// methods
|
|
||||||
void manualLoop(const float dt) {
|
|
||||||
setAllRadioChannelsManually();
|
|
||||||
_headingOutput = _hal->rc[ch_str]->getPosition();
|
|
||||||
_throttleOutput = _hal->rc[ch_thrust]->getPosition();
|
|
||||||
}
|
|
||||||
void autoLoop(const float dt) {
|
|
||||||
float headingError = _guide->getHeadingCommand()
|
|
||||||
- _nav->getYaw();
|
|
||||||
if (headingError > 180 * deg2Rad)
|
|
||||||
headingError -= 360 * deg2Rad;
|
|
||||||
if (headingError < -180 * deg2Rad)
|
|
||||||
headingError += 360 * deg2Rad;
|
|
||||||
_headingOutput = pidStr.update(headingError, -_nav->getYawRate(), dt);
|
|
||||||
_throttleOutput = pidThr.update(_guide->getGroundSpeedCommand()
|
|
||||||
- _nav->getGroundSpeed(), dt);
|
|
||||||
}
|
|
||||||
void setMotorsActive() {
|
|
||||||
// turn all motors off if below 0.1 throttle
|
|
||||||
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
|
|
||||||
setAllRadioChannelsToNeutral();
|
|
||||||
} else {
|
|
||||||
_hal->rc[ch_left]->setPosition(_throttleOutput + _headingOutput);
|
|
||||||
_hal->rc[ch_right]->setPosition(_throttleOutput - _headingOutput);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// attributes
|
|
||||||
enum {
|
|
||||||
k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr
|
|
||||||
};
|
|
||||||
enum {
|
|
||||||
k_pidStr = k_controllersStart, k_pidThr
|
|
||||||
};
|
|
||||||
enum {
|
|
||||||
ch_mode = 0, ch_left, ch_right, ch_str, ch_thrust
|
|
||||||
};
|
|
||||||
BlockPIDDfb pidStr;
|
|
||||||
BlockPID pidThr;
|
|
||||||
float _headingOutput;
|
|
||||||
float _throttleOutput;
|
|
||||||
};
|
|
||||||
|
|
||||||
} // namespace apo
|
|
||||||
|
|
||||||
#endif /* CONTROLLERTANK_H_ */
|
|
||||||
// vim:ts=4:sw=4:expandtab
|
|
|
@ -1 +0,0 @@
|
||||||
include ../libraries/AP_Common/Arduino.mk
|
|
Loading…
Reference in New Issue