ardupilot/ArduBoat/BoatGeneric.h

66 lines
1.7 KiB
C
Raw Normal View History

2011-09-28 21:51:12 -03:00
/*
* BoatGeneric.h
*
* Created on: May 1, 2011
* Author: jgoppert
2011-10-25 20:40:07 -03:00
*
2011-09-28 21:51:12 -03:00
*/
#ifndef BOATGENERIC_H_
#define BOATGENERIC_H_
2011-12-07 17:31:56 -04:00
using namespace apo;
2011-09-28 21:51:12 -03:00
// vehicle options
2011-12-07 17:31:56 -04:00
static const AP_Board::options_t options = AP_Board::opt_gps | AP_Board::opt_baro | AP_Board::opt_compass;
2011-11-29 14:59:44 -04:00
static const MAV_TYPE vehicle = UGV_SURFACE_SHIP;
2011-09-28 21:51:12 -03:00
static const apo::halMode_t halMode = apo::MODE_LIVE;
2011-12-07 17:31:56 -04:00
//static const apo::AP_Board::mode_e = apo::AP_Board::MODE_HIL_CNTL;
static const apo::AP_Board::mode_e = apo::AP_Board::MODE_LIVE;
static const uint8_t heartBeatTimeout = 0;
2011-09-28 21:51:12 -03:00
// algorithm selection
#define CONTROLLER_CLASS ControllerBoat
#define GUIDE_CLASS MavlinkGuide
2011-12-07 17:31:56 -04:00
#define NAVIGATOR_CLASS Navigator_Dcm
2011-09-28 21:51:12 -03:00
// hardware selection
2011-12-07 17:31:56 -04:00
//#define BOARD_TYPE Board_APM1
//#define BOARD_TYPE Board_APM1_2560
#define BOARD_TYPE Board_APM2
2011-09-28 21:51:12 -03:00
// 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;
2011-09-28 21:51:12 -03:00
2011-12-07 17:31:56 -04:00
// controller
static const bool useForwardReverseSwitch = true;
2011-09-28 21:51:12 -03:00
// gains
2011-10-25 20:40:07 -03:00
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;
2011-09-28 21:51:12 -03:00
2011-10-25 20:40:07 -03:00
// guidance
static const float velCmd = 5;
static const float xt = 10;
static const float xtLim = 90;
2011-09-28 21:51:12 -03:00
#include "ControllerBoat.h"
#endif /* BOATGENERIC_H_ */
2011-10-26 14:25:06 -03:00
// vim:ts=4:sw=4:expandtab