Code cleanup.

Re #183.

git-svn-id: https://svn.code.sf.net/p/speed-dreams/code/trunk@2868 30fe4595-0a0c-4342-8851-515496e4dcbd

Former-commit-id: b1ec3262926400581e236f505824e5fe4c1ef4b8
Former-commit-id: 4d4d438a388b54e68650541e572592da6255dd13
This commit is contained in:
kmetykog 2010-10-11 20:54:28 +00:00
parent 0411f21771
commit 9509e422bc
12 changed files with 1078 additions and 1403 deletions

View file

@ -2,9 +2,9 @@ INCLUDE(../../../cmake/macros.cmake)
SET(ROBOT_NAME "kilo2008")
SET(ROBOT_SOURCES ${ROBOT_NAME}.cpp driver.cpp opponent.cpp driver.h pit.cpp strategy.cpp
linalg.h opponent.h strategy.h pit.h cardata.h cardata.cpp spline.cpp
spline.h raceline.cpp raceline.h kdriver.cpp kdriver.h util.h util.cpp)
SET(ROBOT_SOURCES ${ROBOT_NAME}.cpp opponent.cpp pit.cpp strategy.cpp
linalg.h opponent.h strategy.h pit.h cardata.h cardata.cpp spline.cpp
spline.h raceline.cpp raceline.h kdriver.cpp kdriver.h util.h util.cpp)
SET(ROBOT_SHIP logo.rgb)
SET(ROBOT_SHIPSUBDIRS 1 2 tracks trb1-cavallo-360rb)

File diff suppressed because it is too large Load diff

View file

@ -1,210 +0,0 @@
/*
* driver.h
*
* Copyright 2009 kilo aka Gabor Kmetyko <kg.kilo@gmail.com>
* Based on work by Bernhard Wymann and Andrew Sumner.
*
* This program 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
* $Id$
*
*/
#ifndef _DRIVER_H_
#define _DRIVER_H_
#include "cardata.h"
#include "linalg.h" //v2d
#include <track.h> //tTrack
#include <car.h> //tCarElt
#include <raceman.h> //tSituation
#define BT_SECT_PRIV "private"
#define BT_ATT_FUELPERLAP "fuelperlap"
#define BT_ATT_MUFACTOR "mufactor"
#define BT_ATT_PITTIME "pittime"
#define BT_ATT_BESTLAP "bestlap"
#define BT_ATT_WORSTLAP "worstlap"
#define BT_ATT_TEAMMATE "teammate"
class Opponents;
class Opponent;
class Pit;
class KStrategy;
class LRaceLine;
enum
{ NORMAL = 1, AVOIDING, CORRECTING, PITTING, BEING_OVERLAPPED };
enum
{ TEAM_FRIEND = 1, TEAM_FOE };
enum
{ AVOIDLEFT = 1, AVOIDRIGHT = 2, AVOIDSIDE = 4 };
class Driver
{
public:
Driver(int index);
virtual ~Driver();
// Callback functions called from TORCS.
virtual void newRace(tCarElt * car, tSituation * s);
virtual void drive(tSituation * s);
virtual int pitCommand(tSituation * s) = 0;
void endRace(tSituation * s);
tCarElt *getCarPtr() { return m_car;}
tTrack *getTrackPtr() { return m_track;}
double getSpeed() { return m_mycardata->getSpeedInTrackDirection(); }
static const int TEAM_DAMAGE_CHANGE_LEAD; //Used in opponent.cpp too
protected:
// Constants.
enum { NORMAL = 1, AVOIDING, CORRECTING, PITTING, OVERLAPPED };
enum { TEAM_FRIEND = 1, TEAM_FOE };
enum { AVOIDLEFT = 1, AVOIDRIGHT = 2, AVOIDSIDE = 4 };
// Utility functions.
virtual bool isStuck();
virtual void update(tSituation *) = 0;
double getAccel();
double getDistToSegEnd();
double getBrake();
int getGear();
double getSteer(tSituation * s);
double getClutch();
vec2f getTargetPoint();
virtual double getOffset() = 0;
double brakedist(double allowedspeed, double mu);
double smoothSteering(double steercmd);
double correctSteering(double avoidsteer, double racesteer);
double calcSteer(double targetAngle, int rl);
void setMode(int newmode);
double getWidth() { return m_mycardata->getWidthOnTrack();}
virtual void calcSpeed();
virtual void setAvoidRight() = 0;
virtual void setAvoidLeft() = 0;
virtual bool oppTooFarOnSide(tCarElt *) = 0;
virtual double filterOverlap(double accel) = 0;
virtual double filterBColl(double brake) = 0;
double filterABS(double brake);
double filterBPit(double brake);
virtual double filterBrakeSpeed(double brake);
double filterTurnSpeed(double brake);
double filterTCL(const double accel);
void initTCLfilter();
double filterTCL_RWD();
double filterTCL_FWD();
double filterTCL_4WD();
double filterTrk(double accel);
void initCa();
void initCw();
void initTireMu();
// Per robot global data.
int m_mode;
int m_avoidmode;
int m_lastmode;
int m_stuckCounter;
double m_speedangle; // the angle of the speed vector relative to trackangle, > 0.0 points to right.
double m_angle;
double m_mass; // Mass of car + fuel.
double m_myoffset; // Offset to the track middle.
double m_laststeer;
double m_lastNSasteer;
tCarElt *m_car; // Pointer to tCarElt struct.
LRaceLine *m_raceline;
Opponents *m_opponents; // The container for opponents.
Pit *m_pit; // Pointer to the pit instance.
KStrategy *m_strategy; // Pit stop strategy.
tTrack *m_track; // Track variables.
static Cardata *m_cardata; // Data about all cars shared by all instances.
SingleCardata *m_mycardata; // Pointer to "global" data about my car.
static double m_currentSimTime; // Store time to avoid useless updates.
double m_simTime; // how long since the race started
double m_avoidTime; // how long since we began avoiding
double m_correctTimer; // how long we've been correcting
double m_correctLimit; // level of divergence with raceline steering
double m_brakeDelay;
double m_currentSpeedSqr; // Square of the current speed_x.
double m_clutchTime; // Clutch timer.
double m_oldLookahead; // Lookahead for steering in the previous step.
double m_raceSteer; // steer command to get to raceline
double m_rLookahead; // how far ahead on the track we look for steering
double m_raceOffset; // offset from middle of track towards which raceline is steering
double m_avoidLftOffset; // closest opponent on the left
double m_avoidRgtOffset; // closest opponent on the right
double m_raceSpeed; // how fast raceline code says we should be going
double m_avoidSpeed; // how fast we should go if avoiding
double m_accelCmd;
double m_brakeCmd;
double m_pitOffset;
v2d m_raceTarget; // the 2d point the raceline is driving at.
int m_carIndex;
// Data that should stay constant after first initialization.
int MAX_UNSTUCK_COUNT;
int INDEX;
double CARMASS; // Mass of the car only [kg].
double CA; // Aerodynamic downforce coefficient.
double CW; // Aerodynamic drag coefficient.
double TIREMU; // Friction coefficient of tires.
double (Driver::*GET_DRIVEN_WHEEL_SPEED) ();
double OVERTAKE_OFFSET_INC; // [m/timestep]
double MU_FACTOR; // [-]
// Class constants.
static const double MAX_UNSTUCK_ANGLE;
static const double UNSTUCK_TIME_LIMIT;
static const double MAX_UNSTUCK_SPEED;
static const double MIN_UNSTUCK_DIST;
static const double G;
static const double SHIFT;
static const double SHIFT_MARGIN;
static const double ABS_SLIP;
static const double ABS_RANGE;
static const double ABS_MINSPEED;
static const double TCL_SLIP;
static const double LOOKAHEAD_CONST;
static const double LOOKAHEAD_FACTOR;
static const double WIDTHDIV;
static const double BORDER_OVERTAKE_MARGIN;
static const double OVERTAKE_OFFSET_SPEED;
static const double PIT_LOOKAHEAD;
static const double PIT_BRAKE_AHEAD;
static const double PIT_MU;
static const double MAX_SPEED;
static const double TCL_RANGE;
static const double CLUTCH_SPEED;
static const double DISTCUTOFF;
static const double MAX_INC_FACTOR;
static const double CATCH_FACTOR;
static const double TEAM_REAR_DIST;
static const double LET_OVERTAKE_FACTOR;
};
#endif // _DRIVER_H_

View file

@ -26,7 +26,6 @@
#include "kdriver.h"
#include <iostream>
#include <string>
#include <sstream>
#include "opponent.h"
@ -47,19 +46,69 @@
static int
pitstatus[128] = { 0 };
static double colour[] = {1.0, 0.0, 0.0, 0.0};
//Constants
const double KDriver::MAX_UNSTUCK_ANGLE = 15.0 / 180.0 * PI; // [radians] If the angle of the car on the track is smaller, we assume we are not stuck.
const double KDriver::UNSTUCK_TIME_LIMIT = 2.0; // [s] We try to get unstuck after this time.
const double KDriver::MAX_UNSTUCK_SPEED = 5.0; // [m/s] Below this speed we consider being stuck.
const double KDriver::MIN_UNSTUCK_DIST = 3.0; // [m] If we are closer to the middle we assume to be not stuck.
const double KDriver::G = 9.81; // [m/(s*s)] Welcome on Earth.
const double KDriver::SHIFT = 0.95; // [-] (% of rpmredline) When do we like to shift gears.
const double KDriver::SHIFT_MARGIN = 4.4; // [m/s] Avoid oscillating gear changes.
const double KDriver::ABS_SLIP = 2.5; // [m/s] range [0..10]
const double KDriver::ABS_RANGE = 5.0; // [m/s] range [0..10]
const double KDriver::ABS_MINSPEED = 3.0; // [m/s] Below this speed the ABS is disabled (numeric, division by small numbers).
const double KDriver::TCL_SLIP = 2.0; // [m/s] range [0..10]
const double KDriver::TCL_RANGE = 10.0; // [m/s] range [0..10]
const double KDriver::LOOKAHEAD_CONST = 18.0; // [m]
const double KDriver::LOOKAHEAD_FACTOR = 0.33; // [-]
const double KDriver::WIDTHDIV = 2.0; // [-] Defines the percentage of the track to use (2/WIDTHDIV).
const double KDriver::BORDER_OVERTAKE_MARGIN = 1.0; // [m]
const double KDriver::OVERTAKE_OFFSET_SPEED = 5.0; // [m/s] Offset change speed.
const double KDriver::PIT_LOOKAHEAD = 6.0; // [m] Lookahead to stop in the pit.
const double KDriver::PIT_BRAKE_AHEAD = 200.0; // [m] Workaround for "broken" pitentries.
const double KDriver::PIT_MU = 0.4; // [-] Friction of pit concrete.
const double KDriver::MAX_SPEED = 350.0 / 3.6; // [m/s] Speed to compute the percentage of brake to apply., 350 km/h
const double KDriver::CLUTCH_SPEED = 5.0; // [m/s]
const double KDriver::DISTCUTOFF = 400.0; // [m] How far to look, terminate while loops.
const double KDriver::MAX_INC_FACTOR = 8.0; // [m] Increment faster if speed is slow [1.0..10.0].
const double KDriver::CATCH_FACTOR = 10.0; // [-] select MIN(catchdist, dist*CATCH_FACTOR) to overtake.
const double KDriver::TEAM_REAR_DIST = 50.0; //
const double KDriver::LET_OVERTAKE_FACTOR = 0.6; //Reduce speed with this factor when being overlapped
const int KDriver::TEAM_DAMAGE_CHANGE_LEAD = 800;// When to change position in the team?
// Static variables.
Cardata *KDriver::m_cardata = NULL;
double KDriver::m_currentSimTime;
static char const *WheelSect[4] = { SECT_FRNTRGTWHEEL, SECT_FRNTLFTWHEEL,
SECT_REARRGTWHEEL, SECT_REARLFTWHEEL };
#define DEFAULTCARTYPE "trb1-cavallo-360rb"
#define SLOW_TRACK_LIMIT 2.4
#define FAST_TRACK_LIMIT 4.0
KDriver::KDriver(int index):Driver(index)
KDriver::KDriver(int index)
{
INDEX = index;
m_rgtinc = m_lftinc = 0.0;
m_minoffset = m_maxoffset = 0.0;
m_rInverse = 0.0;
}
KDriver::~KDriver()
{
delete m_raceline;
delete m_opponents;
delete m_pit;
delete m_strategy;
if(m_cardata != NULL) {
delete m_cardata;
m_cardata = NULL;
}
}
/**
* Drive during the race.
@ -106,6 +155,13 @@ KDriver::drive(tSituation * s)
}//drive
void
KDriver::endRace(tSituation * s)
{
// Nothing for now.
}//endRace
/**
* Checks if I'm stuck.
*
@ -143,7 +199,7 @@ double
KDriver::filterBrakeSpeed(double brake)
{
double weight = m_mass * G;
double maxForce = weight + CA * MAX_SPEED * MAX_SPEED;
double maxForce = weight + CA * pow(MAX_SPEED, 2);
double force = weight + CA * m_currentSpeedSqr;
return brake * force / maxForce;
}//filterBrakeSpeed
@ -688,12 +744,12 @@ KDriver::initTrack(tTrack * t, void *carHandle, void **carParmHandle,
m_raceline = new LRaceLine;
// Load and set parameters.
MU_FACTOR = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, BT_ATT_MUFACTOR,
(char *) NULL, 0.69f);
m_pitOffset = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "PitOffset",
(char *) NULL, 10.0);
m_brakeDelay = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "BrakeDelay", (char*) NULL, 10.0);
MU_FACTOR =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_MUFACTOR, NULL, 0.69f);
m_pitOffset =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_PITOFFSET, NULL, 10.0);
m_brakeDelay =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_BRDELAY, NULL, 10.0);
m_raceline->InitTrack(m_track, carParmHandle, s);
}//initTrack
@ -806,12 +862,12 @@ KDriver::filterBColl(const double brake)
it++) {
if(it->isState(OPP_COLL)) { //Endangered species
double ospeed = it->getSpeed();
if(brakedist(ospeed, mu) + MIN(1.0, 0.5 + MAX(0.0,(getSpeed() - ospeed) / 4))
if(brakeDist(ospeed, mu) + MIN(1.0, 0.5 + MAX(0.0,(getSpeed() - ospeed) / 4))
> it->getDistance()) { //Damn, too close, brake hard!!!
m_accelCmd = 0.0;
ret = 1.0;
break;
}//if brakedist
}//if brakeDist
}//if state OPP_COLL
}//for it
}//if m_simTime
@ -836,7 +892,48 @@ void
KDriver::newRace(tCarElt * car, tSituation * s)
{
m_strategy->setCar(car);
Driver::newRace(car, s);
double deltaTime = (double) RCM_MAX_DT_ROBOTS;
MAX_UNSTUCK_COUNT = int (UNSTUCK_TIME_LIMIT / deltaTime);
OVERTAKE_OFFSET_INC = OVERTAKE_OFFSET_SPEED * deltaTime;
m_stuckCounter = 0;
m_clutchTime = 0.0;
m_oldLookahead = m_laststeer = m_lastNSasteer = 0.0;
m_car = car;
CARMASS = GfParmGetNum(m_car->_carHandle, SECT_CAR, PRM_MASS, NULL, 1000.0);
m_myoffset = 0.0;
m_simTime = m_correctTimer = 0.0;
m_correctLimit = 1000.0;
initCa();
initCw();
initTireMu();
initTCLFilter();
// Create just one instance of cardata shared by all drivers.
if(m_cardata == NULL)
m_cardata = new Cardata(s);
m_mycardata = m_cardata->findCar(m_car);
m_currentSimTime = s->currentTime;
// initialize the list of opponents.
m_opponents = new Opponents(s, this, m_cardata);
m_opponents->setTeamMate(m_car);
// create the pit object.
m_pit = new Pit(s, this, m_pitOffset);
// set initial mode
//we set it to CORRECTING so the robot will steer towards the raceline
setMode(CORRECTING);
m_lastmode = CORRECTING;
for(m_carIndex = 0; m_carIndex < s->_ncars; m_carIndex++) {
if(s->cars[m_carIndex] == m_car)
break;
}
m_raceline->setCar(m_car);
m_raceline->NewRace();
}//newRace
@ -871,10 +968,8 @@ KDriver::calcSpeed()
/**
* Decides the character of the track
* and chooses 1 of 3 default setups.
* Loads the appropriate setup file and
* returns it's handler.
* Decides the character of the track and chooses 1 of 3 default setups.
* Loads the appropriate setup file and returns it's handler.
*
* @return Handler to the loaded default setup
*/
@ -933,6 +1028,7 @@ KDriver::loadDefaultSetup() const
return ret;
}//loadDefaultSetup
void
KDriver::mergeCarSetups(void *oldHandle, void *newHandle)
{
@ -946,3 +1042,752 @@ KDriver::mergeCarSetups(void *oldHandle, void *newHandle)
oldHandle = newHandle;
}//if newHandle
}//mergeCarSetups
// Compute aerodynamic downforce coefficient CA.
void
KDriver::initCa()
{
double rearWingArea =
GfParmGetNum(m_car->_carHandle, SECT_REARWING, PRM_WINGAREA, NULL, 0.0);
double rearWingAngle =
GfParmGetNum(m_car->_carHandle, SECT_REARWING, PRM_WINGANGLE, NULL, 0.0);
double wingCa = 1.23 * rearWingArea * sin(rearWingAngle);
double cl =
GfParmGetNum(m_car->_carHandle, SECT_AERODYNAMICS, PRM_FCL, NULL, 0.0) +
GfParmGetNum(m_car->_carHandle, SECT_AERODYNAMICS, PRM_RCL, NULL, 0.0);
double h = 0.0;
for(int i = 0; i < 4; i++)
h += GfParmGetNum(m_car->_carHandle, WheelSect[i], PRM_RIDEHEIGHT, NULL, 0.2);
h *= 1.5;
h = pow(h, 4);
h = 2.0 * exp(-3.0 * h);
CA = h * cl + 4.0 * wingCa;
}//initCa
// Compute aerodynamic drag coefficient CW.
void
KDriver::initCw()
{
double cx =
GfParmGetNum(m_car->_carHandle, SECT_AERODYNAMICS, PRM_CX, NULL, 0.0);
double frontArea =
GfParmGetNum(m_car->_carHandle, SECT_AERODYNAMICS, PRM_FRNTAREA, NULL, 0.0);
CW = 0.645 * cx * frontArea;
}//initCw
// Init the friction coefficient of the the tires.
void
KDriver::initTireMu()
{
double tm = DBL_MAX;
for(int i = 0; i < 4; i++)
tm = MIN(tm, GfParmGetNum(m_car->_carHandle, WheelSect[i], PRM_MU, NULL, 1.0));
TIREMU = tm;
}//initTireMu
// Traction Control (TCL) setup.
void
KDriver::initTCLFilter()
{
const string traintype = GfParmGetStr(m_car->_carHandle, SECT_DRIVETRAIN, PRM_TYPE,
VAL_TRANS_RWD);
if(traintype == VAL_TRANS_RWD)
GET_DRIVEN_WHEEL_SPEED = &KDriver::filterTCL_RWD;
else if(traintype == VAL_TRANS_FWD)
GET_DRIVEN_WHEEL_SPEED = &KDriver::filterTCL_FWD;
else if(traintype == VAL_TRANS_4WD)
GET_DRIVEN_WHEEL_SPEED = &KDriver::filterTCL_4WD;
}//initTCLFilter
// TCL filter plugin for rear wheel driven cars.
double
KDriver::filterTCL_RWD()
{
return (m_car->_wheelSpinVel(REAR_RGT) + m_car->_wheelSpinVel(REAR_LFT)) *
m_car->_wheelRadius(REAR_LFT) / 2.0;
}
// TCL filter plugin for front wheel driven cars.
double
KDriver::filterTCL_FWD()
{
return (m_car->_wheelSpinVel(FRNT_RGT) + m_car->_wheelSpinVel(FRNT_LFT)) *
m_car->_wheelRadius(FRNT_LFT) / 2.0;
}
// TCL filter plugin for all wheel driven cars.
double
KDriver::filterTCL_4WD()
{
return ((m_car->_wheelSpinVel(FRNT_RGT) + m_car->_wheelSpinVel(FRNT_LFT)) *
m_car->_wheelRadius(FRNT_LFT) +
(m_car->_wheelSpinVel(REAR_RGT) + m_car->_wheelSpinVel(REAR_LFT)) *
m_car->_wheelRadius(REAR_LFT)) / 4.0;
}
// TCL filter for accelerator pedal.
double
KDriver::filterTCL(const double accel)
{
double ret = accel;
if(m_simTime >= 3.0) {
ret = MIN(1.0, accel);
double accel1 = ret, accel2 = ret, accel3 = ret;
if(m_car->_speed_x > 10.0) {
tTrackSeg *seg = m_car->_trkPos.seg;
tTrackSeg *wseg0 = m_car->_wheelSeg(0);
tTrackSeg *wseg1 = m_car->_wheelSeg(1);
int count = 0;
if(
wseg0->surface->kRoughness > MAX(0.02, seg->surface->kRoughness * 1.2)
|| wseg0->surface->kFriction < seg->surface->kFriction * 0.8
|| wseg0->surface->kRollRes > MAX(0.005, seg->surface->kRollRes * 1.2))
count++;
if(
wseg1->surface->kRoughness > MAX(0.02, seg->surface->kRoughness * 1.2)
|| wseg1->surface->kFriction < seg->surface->kFriction * 0.8
|| wseg1->surface->kRollRes > MAX(0.005, seg->surface->kRollRes * 1.2))
count++;
if(count) {
if(m_mode != NORMAL
&& ((seg->type == TR_RGT && seg->radius <= 200.0
&& m_car->_trkPos.toLeft < 3.0)
|| (seg->type == TR_LFT && seg->radius <= 200.0
&& m_car->_trkPos.toRight < 3.0)))
count++;
accel1 = MAX(0.0, MIN(accel1, (1.0 - (0.25 * count)) -
MAX(0.0, (getSpeed() - m_car->_speed_x) / 10.0)));
}//if count
if(fabs(m_angle) > 1.0)
accel1 = MIN(accel1, 1.0 - (fabs(m_angle) - 1.0) * 1.3);
}//if m_car->_speed_x
if(fabs(m_car->_steerCmd) > 0.02) {
double decel = ((fabs(m_car->_steerCmd) - 0.02) *
(1.0 + fabs(m_car->_steerCmd)) * 0.7);
accel2 = MIN(accel2, MAX(0.45, 1.0 - decel));
}//if m_car->_steerCmd
double slip = (this->*GET_DRIVEN_WHEEL_SPEED) () - m_car->_speed_x;
if(slip > TCL_SLIP)
accel3 = accel3 - MIN(accel3, (slip - TCL_SLIP) / TCL_RANGE);
ret = MIN(accel1, MIN(accel2, accel3));
}//if m_simTime
return ret;
}//filterTCL
// Hold car on the track.
double
KDriver::filterTrk(const double accel)
{
double ret = accel;
tTrackSeg *seg = m_car->_trkPos.seg;
if(m_car->_speed_x >= MAX_UNSTUCK_SPEED // Not too slow
&& !m_pit->getInPit() // Not on pit stop
&& m_car->_trkPos.toMiddle * -m_speedangle <= 0.0) { // Speedvector points to the outside of the turn
if(seg->type == TR_STR) {
double tm = fabs(m_car->_trkPos.toMiddle);
double w = (seg->width - m_car->_dimension_y) / 2.0;
ret = (tm > w) ? 0.0 : accel;
} else {
double sign = (seg->type == TR_RGT) ? -1.0 : 1.0;
if(m_car->_trkPos.toMiddle * sign > 0.0)
ret = accel;
else {
double tm = fabs(m_car->_trkPos.toMiddle);
double w = seg->width / WIDTHDIV;
ret = (tm > w) ? 0.0 : accel;
}
}//if seg->type
}//if not too slow
return ret;
}//filterTrk
// Compute the needed distance to brake.
double
KDriver::brakeDist(double allowedspeed, double mu)
{
double c = mu * G;
double d = (CA * mu + CW) / m_mass;
double v1sqr = m_currentSpeedSqr;
double v2sqr = pow(allowedspeed, 2);
return -log((c + v2sqr * d) / (c + v1sqr * d)) / (2.0 * d);
}//brakeDist
// Antilocking filter for brakes.
double
KDriver::filterABS(double brake)
{
double ret = brake;
if(m_car->_speed_x >= ABS_MINSPEED) {
double origbrake = brake;
double rearskid = MAX(0.0, MAX(m_car->_skid[2], m_car->_skid[3]) -
MAX(m_car->_skid[0], m_car->_skid[1]));
double slip = 0.0;
for(int i = 0; i < 4; i++)
slip += m_car->_wheelSpinVel(i) * m_car->_wheelRadius(i);
slip *=
1.0 + MAX(rearskid, MAX(fabs(m_car->_yaw_rate) / 5, fabs(m_angle) / 6));
slip = m_car->_speed_x - slip / 4.0;
if(slip > ABS_SLIP)
ret = brake - MIN(brake, (slip - ABS_SLIP) / ABS_RANGE);
ret = MAX(ret, MIN(origbrake, 0.1f));
}
return ret;
}//filterABS
// Brake filter for pit stop.
double
KDriver::filterBPit(double brake)
{
double mu = m_car->_trkPos.seg->surface->kFriction * TIREMU * PIT_MU;
if(m_pit->getPitstop() && !m_pit->getInPit()) {
tdble dl, dw;
RtDistToPit(m_car, m_track, &dl, &dw);
if(dl < PIT_BRAKE_AHEAD) {
if(brakeDist(0.0, mu) > dl)
return 1.0;
}
}
if(m_pit->getInPit()) {
double s = m_pit->toSplineCoord(m_car->_distFromStartLine);
// Pit entry.
if(m_pit->getPitstop()) {
if(s < m_pit->getNPitStart()) {
// Brake to pit speed limit.
double dist = m_pit->getNPitStart() - s;
if(brakeDist(m_pit->getSpeedlimit(), mu) > dist)
return 1.0;
} else {
// Hold speed limit.
if(m_currentSpeedSqr > m_pit->getSpeedlimitSqr())
return m_pit->getSpeedLimitBrake(m_currentSpeedSqr);
}//if s
// Brake into pit (speed limit 0.0 to stop)
double dist = m_pit->getNPitLoc() - s;
if(m_pit->isTimeout(dist)) {
m_pit->setPitstop(false);
return 0.0;
} else {
if(brakeDist(0.0, mu) > dist)
return 1.0;
else if(s > m_pit->getNPitLoc())
return 1.0; // Stop in the pit.
}//if pit timeout
} else {
// Pit exit.
if(s < m_pit->getNPitEnd()) {
// Pit speed limit.
if(m_currentSpeedSqr > m_pit->getSpeedlimitSqr())
return m_pit->getSpeedLimitBrake(m_currentSpeedSqr);
}
}
}
return brake;
}//filterBPit
double
KDriver::calcSteer(double targetAngle, int rl)
{
double rearskid = MAX(0.0, MAX(m_car->_skid[2], m_car->_skid[3])
- MAX(m_car->_skid[0], m_car->_skid[1]))
+ MAX(m_car->_skid[2], m_car->_skid[3]) * fabs(m_angle) * 0.9;
double angle_correction = 0.0;
double factor = (rl ? 1.4f : (m_mode == CORRECTING ? 1.1f : 1.2f));
if(m_angle < 0.0)
angle_correction = MAX(m_angle, MIN(0.0, m_angle / 2.0) / MAX(15.0, 70.0 - m_car->_speed_x) * factor);
else
angle_correction = MIN(m_angle, MAX(0.0, m_angle / 2.0) / MAX(15.0, 70.0 - m_car->_speed_x) * factor);
double steer_direction = targetAngle - m_car->_yaw + angle_correction;
NORM_PI_PI(steer_direction);
if(m_car->_speed_x > 10.0) {
double speedsteer = (80.0 - MIN(70.0, MAX(40.0, getSpeed()))) /
((185.0 * MIN(1.0, m_car->_steerLock / 0.785)) +
(185.0 * (MIN(1.3, MAX(1.0, 1.0 + rearskid))) - 185.0));
if(fabs(steer_direction) > speedsteer)
steer_direction = MAX(-speedsteer, MIN(speedsteer, steer_direction));
}
double steer = steer_direction / m_car->_steerLock;
//smooth steering. check for separate function for this!
if(m_mode != PITTING) {
double minspeedfactor = (((105.0 -
MAX(40.0, MIN(70.0, getSpeed() + MAX(0.0, m_car->_accel_x * 5.0))))
/ 300.0) * (5.0 + MAX(0.0, (CA-1.9) * 20.0)));
double maxspeedfactor = minspeedfactor;
double rInverse = m_raceline->getRInverse();
if(rInverse > 0.0) {
minspeedfactor = MAX(minspeedfactor / 3, minspeedfactor - rInverse * 80.0);
maxspeedfactor = MAX(maxspeedfactor / 3, maxspeedfactor + rInverse * 20.0);
} else {
maxspeedfactor = MAX(maxspeedfactor / 3, maxspeedfactor + rInverse * 80.0);
minspeedfactor = MAX(minspeedfactor / 3, minspeedfactor + rInverse * 20.0);
}//if rInverse
steer = MAX(m_lastNSasteer - minspeedfactor, MIN(m_lastNSasteer + maxspeedfactor, steer));
}//if mode != PITTING
m_lastNSasteer = steer;
if(fabs(m_angle) > fabs(m_speedangle)) {
//steer into the skid
double sa = MAX(-0.3, MIN(0.3, m_speedangle / 3));
double anglediff = (sa - m_angle) * (0.7 - MAX(0.0, MIN(0.3, m_car->_accel_x/100)));
//anglediff += m_raceline->getRInverse() * 10;
steer += anglediff * 0.7;
}
if(fabs(m_angle) > 1.2) {
steer = sign(steer);
} else if(fabs(m_car->_trkPos.toMiddle) - m_car->_trkPos.seg->width / 2 > 2.0)
steer = MIN(1.0,
MAX(-1.0, steer * (1.0 +
(fabs(m_car->_trkPos.toMiddle) -
m_car->_trkPos.seg->width / 2) / 14 + fabs(m_angle) / 2)));
if (m_mode != PITTING) {
// limit how far we can steer against raceline
double limit = (90.0 - MAX(40.0, MIN(60.0, m_car->_speed_x))) / (50 + fabs(m_angle) * fabs(m_angle) * 3);
steer = MAX(m_raceSteer - limit, MIN(m_raceSteer + limit, steer));
}
return steer;
}//calcSteer
double
KDriver::correctSteering(double avoidsteer, double racesteer)
{
double steer = avoidsteer;
//double accel = MIN(0.0, m_car->_accel_x);
double speed = MAX(50.0, getSpeed());
//double changelimit = MIN(1.0, m_raceline->correctLimit());
double changelimit = MIN(m_raceline->correctLimit(),
(((120.0 - getSpeed()) / 6000)
* (0.5 + MIN(fabs(avoidsteer), fabs(racesteer)) / 10)));
if(m_mode == CORRECTING && m_simTime > 2.0) {
// move steering towards racesteer...
if(m_correctLimit < 900.0) {
if(steer < racesteer) {
steer = (m_correctLimit >= 0.0)
? racesteer
: MIN(racesteer, MAX(steer, racesteer + m_correctLimit));
} else {
steer = (m_correctLimit <= 0.0)
? racesteer
: MAX(racesteer, MIN(steer, racesteer + m_correctLimit));
}
}
speed -= m_car->_accel_x / 10;
speed = MAX(55.0, MIN(150.0, speed + (speed * speed / 55.0)));
double rInverse = m_raceline->getRInverse() *
(m_car->_accel_x < 0.0 ? 1.0 + fabs(m_car->_accel_x) / 10.0 : 1.0);
double correctspeed = 0.5;
if((rInverse > 0.0 && racesteer > steer) || (rInverse < 0.0 && racesteer < steer))
correctspeed += rInverse * 110.0;
steer = (racesteer > steer)
? MIN(racesteer, steer + changelimit) //steer = MIN(racesteer, steer + (((155.0 - speed) / 10000.0) * correctspeed));
: MAX(racesteer, steer - changelimit);//steer = MAX(racesteer, steer - (((155.0-speed)/10000) * correctspeed));
m_correctLimit = (steer - racesteer);// * 1.08;
}//if mode=correcting
return steer;
}//correctSteering
// try to limit sudden changes in steering
// to avoid loss of control through oversteer.
double
KDriver::smoothSteering(double steercmd)
{
double speedfactor = (((60.0 -
(MAX(40.0, MIN(70.0, getSpeed() + MAX(0.0, m_car->_accel_x * 5)))
- 25)) / 300) * 2.5) / 0.585;
//double rearskid = MAX(0.0, MAX(m_car->_skid[2], m_car->_skid[3]) - MAX(m_car->_skid[0], m_car->_skid[1]));
if(fabs(steercmd) < fabs(m_laststeer)
&& fabs(steercmd) <= fabs(m_laststeer - steercmd))
speedfactor *= 2;
double lftspeedfactor = speedfactor - MIN(0.0f, m_car->_yaw_rate / 10.0);
double rgtspeedfactor = speedfactor + MAX(0.0f, m_car->_yaw_rate / 10.0);
steercmd = MAX(m_laststeer - rgtspeedfactor,
MIN(m_laststeer + lftspeedfactor, steercmd));
return steercmd;
}//smoothSteering
/**
* getSteer
* Computes steer value.
* @param s global situation
* @return steer value range -1...1
*/
double
KDriver::getSteer(tSituation *s)
{
double steer = 0.0;
m_raceline->GetRaceLineData(s, &m_raceTarget, &m_raceSpeed, &m_avoidSpeed,
&m_raceOffset, &m_rLookahead, &m_raceSteer);
vec2f target = getTargetPoint();
double targetAngle = atan2(target.y - m_car->_pos_Y, target.x - m_car->_pos_X);
double avoidsteer = calcSteer(targetAngle, 0);
if(m_mode == PITTING)
return avoidsteer;
targetAngle = atan2(m_raceTarget.y - m_car->_pos_Y, m_raceTarget.x - m_car->_pos_X);
// uncomment the following if we want to use BT steering rather than K1999
// m_raceSteer = calcSteer( targetAngle, 1 );
if(m_mode == AVOIDING &&
(!m_avoidmode
|| (m_avoidmode == AVOIDRIGHT && m_raceOffset >= m_myoffset && m_raceOffset < m_avoidLftOffset)
|| (m_avoidmode == AVOIDLEFT && m_raceOffset <= m_myoffset && m_raceOffset > m_avoidRgtOffset))) {
// we're avoiding, but trying to steer somewhere the raceline takes us.
// hence we'll just correct towards the raceline instead.
setMode(CORRECTING);
}
if(m_mode == CORRECTING &&
(m_lastmode == NORMAL ||
(fabs(m_angle) < 0.2f && fabs(m_raceSteer) < 0.4f
&& fabs(m_laststeer - m_raceSteer) < 0.05
&& ((fabs(m_car->_trkPos.toMiddle) < m_car->_trkPos.seg->width / 2 - 1.0)
|| m_car->_speed_x < 10.0) && m_raceline->isOnLine()))) {
// we're CORRECTING & are now close enough to the raceline to
// switch back to 'normal' mode...
setMode(NORMAL);
}
if(m_mode == NORMAL) {
steer = m_raceSteer;
m_lastNSasteer = m_raceSteer * 0.8;
} else {
if(m_mode != CORRECTING) {
m_correctLimit = 1000.0;
m_correctTimer = m_simTime + 7.0;
steer = smoothSteering(avoidsteer);
} else {
steer = smoothSteering(correctSteering(avoidsteer, m_raceSteer));
}//mode != CORRECTING
if(fabs(m_angle) >= 1.6) {
steer = (steer > 0.0) ? 1.0 : -1.0;
}
}//mode != NORMAL
#if 0
fprintf(stderr,
"%s %d: %c%c %.3f (a%.3f k%.3f) cl=%.3f ct=%.1f myof=%.3f->%.3f\n",
m_car->_name, m_car->_dammage,
(m_mode ==
NORMAL ? 'n' : (m_mode ==
AVOIDING ? 'a' : (m_mode ==
CORRECTING ? 'c' : 'p'))),
(m_avoidmode ==
AVOIDLEFT ? 'l' : (m_avoidmode ==
AVOIDRIGHT ? 'r' : (m_avoidmode ==
(AVOIDLEFT +
AVOIDRIGHT) ? 'b' :
' '))), steer,
avoidsteer, m_raceSteer, m_correctLimit, (m_correctTimer - m_simTime),
m_car->_trkPos.toMiddle, m_myoffset);
fflush(stderr);
#endif
return steer;
}//getSteer
/**
* getTargetPoint
* Computes target point for steering.
* @return 2D coords of the target
*/
vec2f
KDriver::getTargetPoint()
{
double lookahead;
if(m_pit->getInPit()) { // To stop in the pit we need special lookahead values.
lookahead = PIT_LOOKAHEAD;
if(m_currentSpeedSqr > m_pit->getSpeedlimitSqr())
lookahead += m_car->_speed_x * LOOKAHEAD_FACTOR;
} else {
// Usual lookahead.
double speed = MAX(20.0, getSpeed()); //+ MAX(0.0, m_car->_accel_x));
lookahead = LOOKAHEAD_CONST * 1.2 + speed * 0.60;
lookahead = MIN(lookahead, LOOKAHEAD_CONST + (pow(speed, 2) / 7 * 0.15));
// Prevent "snap back" of lookahead on harsh braking.
double cmplookahead = m_oldLookahead - m_car->_speed_x * RCM_MAX_DT_ROBOTS;
lookahead = MAX(cmplookahead, lookahead);
}//if getInPit
m_oldLookahead = lookahead;
// Search for the segment containing the target point.
tTrackSeg *seg = m_car->_trkPos.seg;
double length = getDistToSegEnd();
while(length < lookahead) {
seg = seg->next;
length += seg->length;
}
length = lookahead - length + seg->length;
double fromstart = seg->lgfromstart + length;
// Compute the target point.
double offset = getOffset();
double pitoffset = m_pit->getPitOffset(-100.0, fromstart);
if((m_pit->getPitstop() || m_pit->getInPit()) && pitoffset != -100.0) {
setMode(PITTING);
offset = m_myoffset = pitoffset;
} else if(m_mode == PITTING)
setMode(CORRECTING);
vec2f s;
if(m_mode != PITTING) {
m_raceline->GetPoint(offset, lookahead, &s);
return s;
}
s.x = (seg->vertex[TR_SL].x + seg->vertex[TR_SR].x) / 2.0;
s.y = (seg->vertex[TR_SL].y + seg->vertex[TR_SR].y) / 2.0;
if(seg->type == TR_STR) {
vec2f n((seg->vertex[TR_EL].x - seg->vertex[TR_ER].x) / seg->length,
(seg->vertex[TR_EL].y - seg->vertex[TR_ER].y) / seg->length);
n.normalize();
vec2f d((seg->vertex[TR_EL].x - seg->vertex[TR_SL].x) / seg->length,
(seg->vertex[TR_EL].y - seg->vertex[TR_SL].y) / seg->length);
return s + d * length + (float)offset * n;
} else {
vec2f c(seg->center.x, seg->center.y);
double arc = length / seg->radius;
double arcsign = (seg->type == TR_RGT) ? -1.0 : 1.0;
arc = arc * arcsign;
s = s.rotate(c, arc);
vec2f n, t, rt;
n = c - s;
n.normalize();
t = s + (float)arcsign * (float)offset * n;
if(m_mode != PITTING) {
// bugfix - calculates target point a different way, thus
// bypassing an error in the BT code that sometimes made
// the target closer to the car than lookahead...
m_raceline->GetPoint(offset, lookahead, &rt);
double dx = t.x - m_car->_pos_X;
double dy = t.y - m_car->_pos_Y;
double dist1 = Mag(dx, dy);
dx = rt.x - m_car->_pos_X;
dy = rt.y - m_car->_pos_Y;
double dist2 = Mag(dx, dy);
if(dist2 > dist1)
t = rt;
}//if !PITTING
return t;
}//if seg->type
}//getTargetPoint
/**
* getDistToSegEnd
* Computes the length to the end of the segment.
*
* @return distance to segment end, in meter.
*/
double
KDriver::getDistToSegEnd()
{
const tTrackSeg *seg = m_car->_trkPos.seg;
double ret = (seg->type == TR_STR)
? seg->length - m_car->_trkPos.toStart //simple when straight
: (seg->arc - m_car->_trkPos.toStart) * seg->radius; //uhm, arc
return ret;
}//getDistToSegEnd
void
KDriver::setMode(int newmode)
{
if(m_mode != newmode) {
if(m_mode == NORMAL || m_mode == PITTING) {
m_correctTimer = m_simTime + 7.0;
m_correctLimit = 1000.0;
}
m_mode = newmode;
}//m_mode != newmode
}//setMode
/**
* getAccel
* Computes fitting acceleration.
*
* @return Acceleration scaled 0-1.
*/
double
KDriver::getAccel()
{
double ret = 1.0;
if(m_car->_gear > 0) {
m_accelCmd = MIN(1.0, m_accelCmd);
if(fabs(m_angle) > 0.8 && getSpeed() > 10.0)
m_accelCmd = MAX(0.0, MIN(m_accelCmd, 1.0 - getSpeed() / 100.0 * fabs(m_angle)));
ret = m_accelCmd;
}//if m_car->_gear
return ret;
}//getAccel
/**
* getBrake
* Computes initial brake value.
*
* @return brake scaled 0-1
*/
double
KDriver::getBrake()
{
double ret = (m_car->_speed_x < -MAX_UNSTUCK_SPEED)
? 1.0 //Car drives backward, brake
: m_brakeCmd; //Car drives forward, normal braking.
return ret;
}//getBrake
// Compute gear.
int
KDriver::getGear()
{
int ret = m_car->_gear <= 0 ? 1 : m_car->_gear;
if(m_car->_gear > 0) {
double gr_up = m_car->_gearRatio[m_car->_gear + m_car->_gearOffset];
double omega = m_car->_enginerpmRedLine / gr_up;
double wr = m_car->_wheelRadius(2);
if(omega * wr * SHIFT < m_car->_speed_x) {
ret = m_car->_gear + 1;
} else {
double gr_down = m_car->_gearRatio[m_car->_gear + m_car->_gearOffset - 1];
omega = m_car->_enginerpmRedLine / gr_down;
if(m_car->_gear > 1 && omega * wr * SHIFT > m_car->_speed_x + SHIFT_MARGIN)
ret = m_car->_gear - 1;
}
}//if gear > 0
return ret;
}//getGear
// Compute the clutch value.
double
KDriver::getClutch()
{
//???
if(1 || m_car->_gearCmd > 1) {
double maxtime = MAX(0.06, 0.32 - (m_car->_gearCmd / 65.0));
if(m_car->_gear != m_car->_gearCmd)
m_clutchTime = maxtime;
if(m_clutchTime > 0.0)
m_clutchTime -= (RCM_MAX_DT_ROBOTS *
(0.02 + (m_car->_gearCmd / 8.0)));
return 2.0 * m_clutchTime;
} else {//unreachable code???
double drpm = m_car->_enginerpm - m_car->_enginerpmRedLine / 2.0;
double ctlimit = 0.9;
if(m_car->_gearCmd > 1)
ctlimit -= 0.15 + m_car->_gearCmd / 13.0;
m_clutchTime = MIN(ctlimit, m_clutchTime);
if(m_car->_gear != m_car->_gearCmd)
m_clutchTime = 0.0;
double clutcht = (ctlimit - m_clutchTime) / ctlimit;
if(m_car->_gear == 1 && m_car->_accelCmd > 0.0)
m_clutchTime += RCM_MAX_DT_ROBOTS;
if(m_car->_gearCmd == 1 || drpm > 0) {
double speedr;
if(m_car->_gearCmd == 1) {
// Compute corresponding speed to engine rpm.
double omega =
m_car->_enginerpmRedLine / m_car->_gearRatio[m_car->_gear +
m_car->_gearOffset];
double wr = m_car->_wheelRadius(2);
speedr = (CLUTCH_SPEED +
MAX(0.0, m_car->_speed_x)) / fabs(wr * omega);
double clutchr = MAX(0.0,
(1.0 - speedr * 2.0 * drpm /
m_car->_enginerpmRedLine)) *
(m_car->_gearCmd ==
1 ? 0.95 : (0.7 - (m_car->_gearCmd) / 30.0));
return MIN(clutcht, clutchr);
} else {
// For the reverse gear.
m_clutchTime = 0.0;
return 0.0;
}
} else {
return clutcht;
}
}
}//getClutch

View file

@ -26,48 +26,166 @@
#ifndef _KDRIVER_H_
#define _KDRIVER_H_
#include "driver.h" //class Driver
#include "cardata.h"
#include "linalg.h" //v2d
#include <car.h> //tCarElt
#include <raceman.h> //tSituation
#include <string>
class KDriver: public Driver
class Opponents;
class Opponent;
class Pit;
class KStrategy;
class LRaceLine;
//Custom setup features
#define KILO_SECT_PRIV "KiloPrivate"
#define KILO_ATT_FUELPERLAP "FuelPerLap"
#define KILO_ATT_MUFACTOR "MuFactor"
#define KILO_ATT_PITTIME "PitTime"
#define KILO_ATT_BESTLAP "BestLap"
#define KILO_ATT_WORSTLAP "WorstLap"
#define KILO_ATT_TEAMMATE "Teammate"
#define KILO_ATT_MINCORNER "MinCornerInverse"
#define KILO_ATT_CORNERSP "CornerSpeed"
#define KILO_ATT_AVOIDSP "AvoidSpeedAdjust"
#define KILO_ATT_CORNERACC "CornerAccel"
#define KILO_ATT_INTMARG "IntMargin"
#define KILO_ATT_EXTMARG "ExtMargin"
#define KILO_ATT_BRDELAY "BrakeDelay"
#define KILO_ATT_SECRAD "SecurityRadius"
#define KILO_ATT_PITOFFSET "PitOffset"
enum { NORMAL = 1, AVOIDING, CORRECTING, PITTING, BEING_OVERLAPPED };
enum { TEAM_FRIEND = 1, TEAM_FOE };
enum { AVOIDLEFT = 1, AVOIDRIGHT = 2, AVOIDSIDE = 4 };
class KDriver
{
public:
KDriver(int index);
virtual ~KDriver() {};
virtual ~KDriver();
//Callback for TORCS
//Callback functions for the sim
void drive(tSituation * s);
int pitCommand(tSituation * s);
void initTrack(tTrack * t, void *carHandle, void **carParmHandle,
tSituation * s);
void newRace(tCarElt * car, tSituation * s);
void endRace(tSituation * s);
std::string bot; //to make it possible to differentiate between Kilo & Dots
//Used by Opponents
tCarElt *getCarPtr() { return m_car;}
tTrack *getTrackPtr() { return m_track;}
double getSpeed() { return m_mycardata->getSpeedInTrackDirection(); }
protected:
//inherited from Driver
bool isStuck();
//Initialize
void initCa();
void initCw();
void initTireMu();
void initTCLFilter();
//Driving aids
double filterTCL_RWD();
double filterTCL_FWD();
double filterTCL_4WD();
double filterTCL(const double accel);
double filterTrk(double accel);
double brakeDist(double allowedspeed, double mu);
double filterABS(double brake);
double filterBPit(double brake);
//Steering
double getSteer(tSituation * s);
double calcSteer(double targetAngle, int rl);
double correctSteering(double avoidsteer, double racesteer);
double smoothSteering(double steercmd);
vec2f getTargetPoint();
//'own' utilities
void update(tSituation * s);
double filterBrakeSpeed(double brake);
double filterBColl(double brake);
double filterOverlap(double accel);
double getOffset();
void calcSpeed();
void setAvoidRight() {m_avoidmode |= AVOIDRIGHT;}
void setAvoidLeft() {m_avoidmode |= AVOIDLEFT;}
void setMode(int newmode);
bool oppTooFarOnSide(tCarElt *ocar);
//'own' utilities
bool isStuck();
double getDistToSegEnd();
double getOffset();
double getAccel();
double getBrake();
int getGear();
double getClutch();
double getWidth() { return m_mycardata->getWidthOnTrack();}
void checkPitStatus(tSituation *s);
void * loadDefaultSetup() const;
void mergeCarSetups(void *oldHandle, void *newHandle);
//Opponent handling
Opponent * getOverlappingOpp();
Opponent * getTakeoverOpp();
Opponent * getSidecollOpp();
double filterOverlappedOffset(Opponent *o);
double filterTakeoverOffset(Opponent *o);
double filterSidecollOffset(Opponent *o, const double);
void checkPitStatus(tSituation *s);
void * loadDefaultSetup() const;
void mergeCarSetups(void *oldHandle, void *newHandle);
//'own' variables
// Constants.
enum { NORMAL = 1, AVOIDING, CORRECTING, PITTING, OVERLAPPED };
enum { TEAM_FRIEND = 1, TEAM_FOE };
enum { AVOIDLEFT = 1, AVOIDRIGHT = 2, AVOIDSIDE = 4 };
tCarElt *m_car; // Pointer to tCarElt struct.
LRaceLine *m_raceline;
Opponents *m_opponents; // The container for opponents.
Pit *m_pit; // Pointer to the pit instance.
KStrategy *m_strategy; // Pit stop strategy.
tTrack *m_track; // Track variables.
static Cardata *m_cardata; // Data about all cars shared by all instances.
SingleCardata *m_mycardata; // Pointer to "global" data about my car.
static double m_currentSimTime; // Store time to avoid useless updates.
//Per robot global data
int m_mode;
int m_avoidmode;
int m_lastmode;
int m_stuckCounter;
double m_speedangle; // the angle of the speed vector relative to trackangle, > 0.0 points to right.
double m_angle;
double m_mass; // Mass of car + fuel.
double m_myoffset; // Offset to the track middle.
double m_laststeer;
double m_lastNSasteer;
double m_simTime; // how long since the race started
double m_avoidTime; // how long since we began avoiding
double m_correctTimer; // how long we've been correcting
double m_correctLimit; // level of divergence with raceline steering
double m_brakeDelay;
double m_currentSpeedSqr; // Square of the current speed_x.
double m_clutchTime; // Clutch timer.
double m_oldLookahead; // Lookahead for steering in the previous step.
double m_raceSteer; // steer command to get to raceline
double m_rLookahead; // how far ahead on the track we look for steering
double m_raceOffset; // offset from middle of track towards which raceline is steering
double m_avoidLftOffset; // closest opponent on the left
double m_avoidRgtOffset; // closest opponent on the right
double m_raceSpeed; // how fast raceline code says we should be going
double m_avoidSpeed; // how fast we should go if avoiding
double m_accelCmd;
double m_brakeCmd;
double m_pitOffset;
v2d m_raceTarget; // the 2d point the raceline is driving at.
double m_mincatchdist;
double m_rgtinc;
double m_lftinc;
@ -75,6 +193,49 @@ protected:
double m_minoffset;
double m_rInverse;
std::string m_carType;
int m_carIndex;
// Data that should stay constant after first initialization.
int MAX_UNSTUCK_COUNT;
int INDEX;
double CARMASS; // Mass of the car only [kg].
double CA; // Aerodynamic downforce coefficient.
double CW; // Aerodynamic drag coefficient.
double TIREMU; // Friction coefficient of tires.
double OVERTAKE_OFFSET_INC; // [m/timestep]
double MU_FACTOR; // [-]
double (KDriver::*GET_DRIVEN_WHEEL_SPEED) ();
// Class constants.
static const double MAX_UNSTUCK_ANGLE;
static const double UNSTUCK_TIME_LIMIT;
static const double MAX_UNSTUCK_SPEED;
static const double MIN_UNSTUCK_DIST;
static const double G;
static const double SHIFT;
static const double SHIFT_MARGIN;
static const double ABS_SLIP;
static const double ABS_RANGE;
static const double ABS_MINSPEED;
static const double TCL_SLIP;
static const double LOOKAHEAD_CONST;
static const double LOOKAHEAD_FACTOR;
static const double WIDTHDIV;
static const double BORDER_OVERTAKE_MARGIN;
static const double OVERTAKE_OFFSET_SPEED;
static const double PIT_LOOKAHEAD;
static const double PIT_BRAKE_AHEAD;
static const double PIT_MU;
static const double MAX_SPEED;
static const double TCL_RANGE;
static const double CLUTCH_SPEED;
static const double DISTCUTOFF;
static const double MAX_INC_FACTOR;
static const double CATCH_FACTOR;
static const double TEAM_REAR_DIST;
static const double LET_OVERTAKE_FACTOR;
public:
static const int TEAM_DAMAGE_CHANGE_LEAD; //Used in opponent.cpp too
};
#endif // _KDRIVER_H_

View file

@ -27,7 +27,7 @@
#include <iostream>
#include <algorithm>
#include "driver.h"
#include "kdriver.h"
#include "util.h" //Between
// class variables and constants.
@ -62,7 +62,7 @@ Opponent::Opponent(tCarElt *car, SingleCardata * cardata, int index)
void
Opponent::update(tSituation *s, Driver *driver)
Opponent::update(tSituation *s, KDriver *driver)
{
// Init state of opponent to ignore.
m_state = OPP_IGNORE;
@ -204,7 +204,7 @@ Opponent::updateOverlapTimer(tSituation * const s, tCarElt * const mycar)
/**
* Returns true, if the other car is our teammate
* and has significantly less damage
* (defined in Driver::TEAM_DAMAGE_CHANGE_LEAD)
* (defined in KDriver::TEAM_DAMAGE_CHANGE_LEAD)
*
* @param mycar pointer to the other car
* @return true, if the opponent is our teammate
@ -213,7 +213,7 @@ bool
Opponent::isQuickerTeammate(tCarElt * const mycar)
{
return (isTeammate()
&& (mycar->_dammage - m_car->_dammage > Driver::TEAM_DAMAGE_CHANGE_LEAD));
&& (mycar->_dammage - m_car->_dammage > KDriver::TEAM_DAMAGE_CHANGE_LEAD));
}//isQuickerTeammate
@ -226,7 +226,7 @@ Opponent::isQuickerTeammate(tCarElt * const mycar)
* @param driver Our own robot
* @param c Opponent car data
*/
Opponents::Opponents(tSituation *s, Driver *driver, Cardata *c)
Opponents::Opponents(tSituation *s, KDriver *driver, Cardata *c)
{
m_opps = new list<Opponent>;
const tCarElt *ownCar = driver->getCarPtr();
@ -259,7 +259,7 @@ Opponents::Opponents(tSituation *s, Driver *driver, Cardata *c)
* @param driver Our own robot
*/
void
Opponents::update(tSituation *s, Driver *driver)
Opponents::update(tSituation *s, KDriver *driver)
{
//for_each(begin(), end(), update);
for(list<Opponent>::iterator it = begin(); it != end(); it++)
@ -281,7 +281,7 @@ void
Opponents::setTeamMate(const tCarElt *car)
{
string teammate(
GfParmGetStr(car->_paramsHandle, BT_SECT_PRIV, BT_ATT_TEAMMATE, ""));
GfParmGetStr(car->_paramsHandle, KILO_SECT_PRIV, KILO_ATT_TEAMMATE, ""));
list<Opponent>::iterator found = find(begin(), end(), teammate);
if(found != end())

View file

@ -33,7 +33,7 @@
#include <string>
using namespace std;
class Driver;
class KDriver;
#define OPP_IGNORE 0
#define OPP_FRONT (1<<0)
@ -66,7 +66,7 @@ public:
{return (dMiddle > m_car->_trkPos.toMiddle) ? true : false;}
inline void markAsTeamMate() {m_teammate = true;}
void update(tSituation *s, Driver *driver);
void update(tSituation *s, KDriver *driver);
private:
double getDistToSegStart() const;
@ -104,10 +104,10 @@ private:
class Opponents
{
public:
Opponents(tSituation *s, Driver *driver, Cardata *cardata);
Opponents(tSituation *s, KDriver *driver, Cardata *cardata);
~Opponents() {delete m_opps;}
void update(tSituation *s, Driver *driver);
void update(tSituation *s, KDriver *driver);
void setTeamMate(const tCarElt *car);
Opponent *getOppByState(const int state);

View file

@ -25,13 +25,13 @@
#include "pit.h"
#include "driver.h"
#include "kdriver.h"
const double
Pit::SPEED_LIMIT_MARGIN = 0.5; // [m/s] safety margin to avoid pit speeding.
Pit::Pit(const tSituation * s, Driver * driver, const double pitoffset)
Pit::Pit(const tSituation * s, KDriver * driver, const double pitoffset)
{
m_track = driver->getTrackPtr();
m_car = driver->getCarPtr();

View file

@ -26,16 +26,17 @@
#ifndef _PIT_H_
#define _PIT_H_
#include <track.h> //tTrack
//#include <track.h> //tTrack
#include <raceman.h> //tSituation
#include "spline.h"
class Driver;
class KDriver;
//class tTrack;
class Pit
{
public:
Pit(const tSituation * s, Driver * driver, const double PitOffset);
Pit(const tSituation * s, KDriver * driver, const double PitOffset);
~Pit();
void setPitstop(const bool pitstop);

View file

@ -28,7 +28,7 @@
#include <algorithm> //for_each
#include "linalg.h" //v2d
#include "util.h" //Mag, sign, Between*
#include "driver.h" //BT_SECT...
#include "kdriver.h" //KILO_SECT...
////////////////////////////////////////////////////////////////////////////
// Parameters
@ -481,25 +481,21 @@ void
LRaceLine::InitTrack(const tTrack * const track, void **carParmHandle, const tSituation *s)
{
m_dMinCornerInverse =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "MinCornerInverse",
(char *) NULL, 0.002);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_MINCORNER, NULL, 0.002);
m_dCornerSpeed =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "CornerSpeed",
(char *) NULL, 15.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_CORNERSP, NULL, 15.0);
m_dAvoidSpeedAdjust =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "AvoidSpeedAdjust",
(char *) NULL, 2.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_AVOIDSP, NULL, 2.0);
m_dCornerAccel =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "CornerAccel",
(char *) NULL, 1.0);
m_dIntMargin = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "IntMargin",
(char *) NULL, 1.0);
m_dExtMargin = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "ExtMargin",
(char *) NULL, 2.0);
m_dBrakeDelay = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "BrakeDelay",
(char *) NULL, 10.0);
m_dSecurityRadius = GfParmGetNum(*carParmHandle, BT_SECT_PRIV, "securityradius",
(char *) NULL, 100.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_CORNERACC, NULL, 1.0);
m_dIntMargin =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_INTMARG, NULL, 1.0);
m_dExtMargin =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_EXTMARG, NULL, 2.0);
m_dBrakeDelay =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_BRDELAY, NULL, 10.0);
m_dSecurityRadius =
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_SECRAD, NULL, 100.0);
// split track
for(int rl = LINE_MID; rl <= LINE_RL; rl++)

View file

@ -25,7 +25,7 @@
#include "strategy.h"
#include "driver.h" //BT_ATT, BT_SECT
#include "kdriver.h" //KILO_ATT, KILO_SECT
#define MAXFUEL_FOR_THIS_RACE 60.0
//#define STRAT_DEBUG
@ -68,16 +68,16 @@ KStrategy::setFuelAtRaceStart(const tTrack * const t,
{
// Load and set parameters.
const double fuel =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, BT_ATT_FUELPERLAP,
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_FUELPERLAP,
NULL, t->length * MAX_FUEL_PER_METER);
m_expectedfuelperlap = fuel;
// Pittime is pittime without refuel.
m_pittime =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, BT_ATT_PITTIME, NULL, 25.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_PITTIME, NULL, 25.0);
m_bestlap =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, BT_ATT_BESTLAP, NULL, 87.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_BESTLAP, NULL, 87.0);
m_worstlap =
GfParmGetNum(*carParmHandle, BT_SECT_PRIV, BT_ATT_WORSTLAP, NULL, 87.0);
GfParmGetNum(*carParmHandle, KILO_SECT_PRIV, KILO_ATT_WORSTLAP, NULL, 87.0);
//Fuel tank capacity
const double maxfuel =
GfParmGetNum(*carParmHandle, SECT_CAR, PRM_TANK, NULL, 100.0);

View file

@ -3,8 +3,8 @@
<!DOCTYPE params SYSTEM "../../../src/libs/tgf/params.dtd">
<params name="track-spec" type="template" mode="mw">
<section name="private">
<attnum name="PitOffset" val="0.0"/>
<attnum name="SecurityRadius" val="100.0"/>
</section>
<section name="KiloPrivate">
<attnum name="PitOffset" val="0.0"/>
<attnum name="SecurityRadius" val="100.0"/>
</section>
</params>