1) Improved AI. The AI still have some problems in tight curves and S curves,

but should be better than before. Basically the estimation of the turn
   radius was completely wrong and was replaced by a new and better
   algorithm.
2) Introduced new AI base class which has some common functions and variables.
3) Removed unused file auto_kart.hpp.


git-svn-id: svn+ssh://svn.code.sf.net/p/supertuxkart/code/main/trunk@5102 178a84e3-b1eb-0310-8ba1-8eac791a3b58
This commit is contained in:
hikerstk 2010-03-31 21:53:32 +00:00
parent e6654f3c13
commit f2c2d68c77
15 changed files with 412 additions and 573 deletions

View File

@ -150,6 +150,8 @@ supertuxkart_SOURCES = \
items/rubber_band.cpp \
items/rubber_band.hpp \
karts/auto_kart.hpp \
karts/controller/ai_base_controller.cpp \
karts/controller/ai_base_controller.hpp \
karts/controller/controller.cpp \
karts/controller/controller.hpp \
karts/controller/default_ai_controller.cpp \

View File

@ -487,6 +487,10 @@
<Filter
Name="controller"
>
<File
RelativePath="..\..\karts\controller\ai_base_controller.cpp"
>
</File>
<File
RelativePath="..\..\karts\controller\controller.cpp"
>
@ -1286,10 +1290,6 @@
<Filter
Name="karts"
>
<File
RelativePath="..\..\karts\auto_kart.hpp"
>
</File>
<File
RelativePath="..\..\karts\kart.hpp"
>
@ -1317,6 +1317,10 @@
<Filter
Name="controller"
>
<File
RelativePath="..\..\karts\controller\ai_base_controller.hpp"
>
</File>
<File
RelativePath="..\..\karts\controller\controller.hpp"
>

View File

@ -1,41 +0,0 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006 Eduardo Hernandez Munoz, Steve Baker
//
// 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 3
// 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., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_AUTOKART_HPP
#define HEADER_AUTOKART_HPP
#include "irrlicht.h"
#include "karts/kart.hpp"
#include "karts/kart_properties.hpp"
class AutoKart : public Kart
{
public:
AutoKart(const std::string& ident, int position,
const btTransform& init_pos) :
Kart(ident, position, init_pos) {}
bool isPlayerKart() const {return false;}
}; // AutoKart
#endif
/* EOF */

View File

@ -0,0 +1,189 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2006-2009 Eduardo Hernandez Munoz
// Copyright (C) 2009, 2010 Joerg Henrichs
//
// 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 3
// 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., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#include "karts/controller/ai_base_controller.hpp"
#include "karts/kart.hpp"
#include "modes/linear_world.hpp"
#include "tracks/track.hpp"
#include "utils/constants.hpp"
AIBaseController::AIBaseController(Kart *kart,
StateManager::ActivePlayer *player)
: Controller(kart, player)
{
m_kart = kart;
m_kart_length = m_kart->getKartProperties()->getKartModel()->getLength();
m_kart_width = m_kart->getKartProperties()->getKartModel()->getWidth();
m_world = dynamic_cast<LinearWorld*>(World::getWorld());
m_track = m_world->getTrack();
m_quad_graph = &m_track->getQuadGraph();
} // AIBaseController
//-----------------------------------------------------------------------------
/** Returns the next sector of the given sector index. This is used
* for branches in the quad graph to select which way the AI kart should
* go. This is a very simple implementation that always returns the first
* successor.
* \param index Index of the graph node for which the successor is searched.
* \return Returns the successor of this graph node.
*/
unsigned int AIBaseController::getNextSector(unsigned int index)
{
std::vector<unsigned int> successors;
m_quad_graph->getSuccessors(index, successors);
return successors[0];
} // getNextSector
//-----------------------------------------------------------------------------
/** This function steers towards a given angle. It also takes a plunger
** attached to this kart into account by modifying the actual steer angle
* somewhat to simulate driving without seeing.
*/
float AIBaseController::steerToAngle(const unsigned int sector,
const float add_angle)
{
float angle = m_quad_graph->getAngleToNext(sector, getNextSector(sector));
//Desired angle minus current angle equals how many angles to turn
float steer_angle = angle - m_kart->getHeading();
if(m_kart->hasViewBlockedByPlunger())
steer_angle += add_angle*0.2f;
else
steer_angle += add_angle;
steer_angle = normalizeAngle( steer_angle );
return steer_angle;
} // steerToAngle
//-----------------------------------------------------------------------------
/** Sets when skidding will be used: when the ratio of steering angle to
* maximumn steering angle is larger than the fraction set here,
* skidding will be used. This is used to set more aggressive skidding
* for higher level AIs.
* \param f Fraction with which steering angle / max steering angle is
* compared to determine if skidding is used.
*/
void AIBaseController::setSkiddingFraction(float f)
{
m_skidding_threshold = f;
} // setSkiddingFactor
//-----------------------------------------------------------------------------
/** Computes the steering angle to reach a certain point. The function will
* request steering by setting the steering angle to maximum steer angle
* times skidding factor.
* \param point Point to steer towards.
* \param skidding_factor Increase factor for steering when skidding.
* \return Steer angle to use to reach this point.
*/
float AIBaseController::steerToPoint(const Vec3 &point)
{
// First translate and rotate the point the AI is aiming
// at into the kart's local coordinate system.
btQuaternion q(btVector3(0,1,0), -m_kart->getHeading());
Vec3 p = point - m_kart->getXYZ();
Vec3 lc = quatRotate(q, p);
// Now compute the nexessary radius for the turn. After getting the
// kart local coordinates for the point to aim at, the kart is at
// (0,0) facing straight ahead. The center of the rotation is then
// on the X axis and can be computed by the fact that the distance
// to the kart and to the point to aim at must be the same:
// r*r = (r-x)*(r-x) + y*y
// where r is the radius (= position on the X axis), and x, y are the
// local coordinates of the point to aim at. Solving for r
// results in r = (x*x+y*y)/2x
float radius = (lc.getX()*lc.getX() + lc.getZ()*lc.getZ())
/ (2.0f*lc.getX());
// sin(steern_angle) = wheel_base / radius:
float sin_steer_angle = m_kart->getKartProperties()->getWheelBase()/radius;
// If the wheel base is too long (i.e. the minimum radius is too large
// to actually reach the target), make sure that skidding is used
if(sin_steer_angle <= -1.0f)
return -m_kart->getMaxSteerAngle()*m_skidding_threshold-0.1f;
if(sin_steer_angle >= 1.0f)
return m_kart->getMaxSteerAngle()*m_skidding_threshold+0.1f;
float steer_angle = asin(sin_steer_angle);
return steer_angle;
} // steerToPoint
//-----------------------------------------------------------------------------
/** Normalises an angle to be between -pi and _ pi.
* \param angle Angle to normalise.
* \return Normalised angle.
*/
inline float AIBaseController::normalizeAngle(float angle)
{
while( angle > 2*M_PI ) angle -= 2*M_PI;
while( angle < -2*M_PI ) angle += 2*M_PI;
if( angle > M_PI ) angle -= 2*M_PI;
else if( angle < -M_PI ) angle += 2*M_PI;
return angle;
} // normalizeAngle
//-----------------------------------------------------------------------------
/** Converts the steering angle to a lr steering in the range of -1 to 1.
* If the steering angle is too great, it will also trigger skidding. This
* function uses a 'time till full steer' value specifying the time it takes
* for the wheel to reach full left/right steering similar to player karts
* when using a digital input device. The parameter is defined in the kart
* properties and helps somewhat to make AI karts more 'pushable' (since
* otherwise the karts counter-steer to fast).
* It also takes the effect of a plunger into account by restricting the
* actual steer angle to 50% of the maximum.
* \param angle Steering angle.
* \param dt Time step.
*/
void AIBaseController::setSteering(float angle, float dt)
{
float steer_fraction = angle / m_kart->getMaxSteerAngle();
m_controls->m_drift = fabsf(steer_fraction)>=m_skidding_threshold;
if(m_kart->hasViewBlockedByPlunger()) m_controls->m_drift = false;
float old_steer = m_controls->m_steer;
if (steer_fraction > 1.0f) steer_fraction = 1.0f;
else if(steer_fraction < -1.0f) steer_fraction = -1.0f;
if(m_kart->hasViewBlockedByPlunger())
{
if (steer_fraction > 0.5f) steer_fraction = 0.5f;
else if(steer_fraction < -0.5f) steer_fraction = -0.5f;
}
// The AI has its own 'time full steer' value (which is the time
float max_steer_change = dt/m_kart->getKartProperties()->getTimeFullSteerAI();
if(old_steer < steer_fraction)
{
m_controls->m_steer = (old_steer+max_steer_change > steer_fraction)
? steer_fraction : old_steer+max_steer_change;
}
else
{
m_controls->m_steer = (old_steer-max_steer_change < steer_fraction)
? steer_fraction : old_steer-max_steer_change;
}
} // setSteering

View File

@ -0,0 +1,72 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2010 Joerg Henrichs
//// $Id
// 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 3
// 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., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_AI_BASE_CONTROLLER_HPP
#define HEADER_AI_BASE_CONTROLLER_HPP
#include "karts/controller/controller.hpp"
#include "states_screens/state_manager.hpp"
class LinearWorld;
class QuadGraph;
class Track;
class Vec3;
/** A base class for all AI karts. This class basically provides some
* common low level functions.
*/
class AIBaseController : public Controller
{
private:
/** The minimum steering angle at which the AI adds skidding. Lower values
* tend to improve the line the AI is driving. This is used to adjust for
* different AI levels.
*/
float m_skidding_threshold;
protected:
/** Length of the kart, storing it here saves many function calls. */
float m_kart_length;
/** Cache width of kart. */
float m_kart_width;
/** Keep a pointer to the track to reduce calls */
Track *m_track;
/** Keep a pointer to world. */
LinearWorld *m_world;
/** The graph of qudas of this track. */
const QuadGraph *m_quad_graph;
float steerToAngle (const unsigned int sector, const float angle);
float steerToPoint (const Vec3 &point);
float normalizeAngle(float angle);
void setSteering (float angle, float dt);
void setSkiddingFraction(float f);
virtual unsigned int getNextSector(unsigned int index);
public:
AIBaseController(Kart *kart,
StateManager::ActivePlayer *player=NULL);
virtual ~AIBaseController() {};
};
#endif
/* EOF */

View File

@ -1,3 +1,5 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2010 Joerg Henrichs
//

View File

@ -1,3 +1,5 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2010 Joerg Henrichs
//

View File

@ -1,3 +1,5 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
@ -44,14 +46,8 @@
#include "tracks/track.hpp"
#include "utils/constants.hpp"
DefaultAIController::DefaultAIController(Kart *kart) : Controller(kart)
DefaultAIController::DefaultAIController(Kart *kart) : AIBaseController(kart)
{
m_kart = kart;
m_kart_length = m_kart->getKartProperties()->getKartModel()->getLength();
m_kart_width = m_kart->getKartProperties()->getKartModel()->getWidth();
m_world = dynamic_cast<LinearWorld*>(World::getWorld());
m_track = m_world->getTrack();
m_quad_graph = &m_track->getQuadGraph();
m_next_node_index.reserve(m_quad_graph->getNumNodes());
m_successor_index.reserve(m_quad_graph->getNumNodes());
@ -116,9 +112,9 @@ DefaultAIController::DefaultAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_TEN_SECONDS;
m_max_start_delay = 0.5f;
m_min_steps = 0;
m_skidding_threshold = 4.0f;
m_nitro_level = NITRO_NONE;
m_handle_bomb = false;
setSkiddingFraction(4.0f);
break;
case RaceManager::RD_MEDIUM:
m_wait_for_players = true;
@ -130,9 +126,9 @@ DefaultAIController::DefaultAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_CALCULATE;
m_max_start_delay = 0.4f;
m_min_steps = 1;
m_skidding_threshold = 2.0f;
m_nitro_level = NITRO_SOME;
m_handle_bomb = true;
setSkiddingFraction(3.0f);
break;
case RaceManager::RD_HARD:
m_wait_for_players = false;
@ -141,9 +137,9 @@ DefaultAIController::DefaultAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_CALCULATE;
m_max_start_delay = 0.1f;
m_min_steps = 2;
m_skidding_threshold = 1.3f;
m_nitro_level = NITRO_ALL;
m_handle_bomb = true;
setSkiddingFraction(2.0f);
break;
}
@ -171,6 +167,16 @@ const irr::core::stringw& DefaultAIController::getNamePostfix() const
return name;
} // getNamePostfix
//-----------------------------------------------------------------------------
/** Returns the pre-computed successor of a graph node.
* \parameter index The index of the graph node for which the successor
* is searched.
*/
unsigned int DefaultAIController::getNextSector(unsigned int index)
{
return m_successor_index[index];
} // getNextSector
//-----------------------------------------------------------------------------
//TODO: if the AI is crashing constantly, make it move backwards in a straight
//line, then move forward while turning.
@ -242,8 +248,7 @@ void DefaultAIController::update(float dt)
/ (m_kart->getSpeed()-m_kart_ahead->getSpeed());
target += m_kart_ahead->getVelocity()*time_till_hit;
}
float steer_angle = steerToPoint(m_kart_ahead->getXYZ(),
dt);
float steer_angle = steerToPoint(m_kart_ahead->getXYZ());
setSteering(steer_angle, dt);
commands_set = true;
}
@ -309,7 +314,10 @@ void DefaultAIController::handleBraking()
kart_ang_diff = normalizeAngle(kart_ang_diff);
kart_ang_diff = fabsf(kart_ang_diff);
const float MIN_TRACK_ANGLE = DEGREE_TO_RAD*20.0f;
// FIXME: The original min_track_angle value of 20 degrees
// resulted in way too much braking. Is this test
// actually necessary at all???
const float MIN_TRACK_ANGLE = DEGREE_TO_RAD*60.0f;
const float CURVE_INSIDE_PERC = 0.25f;
//Brake only if the road does not goes somewhat straight.
@ -370,8 +378,7 @@ void DefaultAIController::handleSteering(float dt)
if( fabsf(m_world->getDistanceToCenterForKart( m_kart->getWorldKartId() )) >
0.5f* m_quad_graph->getNode(m_track_node).getPathWidth()+0.5f )
{
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter(),
dt );
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter());
#ifdef AI_DEBUG
m_debug_sphere->setPosition(m_quad_graph->getQuad(next).getCenter().toIrrVector());
@ -428,7 +435,7 @@ void DefaultAIController::handleSteering(float dt)
#ifdef AI_DEBUG
m_debug_sphere->setPosition(straight_point.toIrrVector());
#endif
steer_angle = steerToPoint(straight_point, dt);
steer_angle = steerToPoint(straight_point);
}
break;
@ -771,78 +778,6 @@ void DefaultAIController::handleNitroAndZipper()
} // handleNitroAndZipper
//-----------------------------------------------------------------------------
float DefaultAIController::steerToAngle(const size_t SECTOR, const float ANGLE)
{
float angle = m_quad_graph->getAngleToNext(SECTOR,
m_successor_index[SECTOR]);
//Desired angle minus current angle equals how many angles to turn
float steer_angle = angle - m_kart->getHeading();
if(m_kart->hasViewBlockedByPlunger())
steer_angle += ANGLE/5;
else
steer_angle += ANGLE;
steer_angle = normalizeAngle( steer_angle );
return steer_angle;
} // steerToAngle
//-----------------------------------------------------------------------------
/** Computes the steering angle to reach a certain point. Note that the
* steering angle depends on the velocity of the kart (simple setting the
* steering angle towards the angle the point has is not correct: a slower
* kart will obviously turn less in one time step than a faster kart).
* \param point Point to steer towards.
* \param dt Time step.
*/
float DefaultAIController::steerToPoint(const Vec3 &point, float dt)
{
// No sense steering if we are not driving.
if(m_kart->getSpeed()==0) return 0.0f;
const float dx = point.getX() - m_kart->getXYZ().getX();
const float dz = point.getZ() - m_kart->getXYZ().getZ();
/** Angle from the kart position to the point in world coordinates. */
float theta = atan2(dx, dz);
// Angle is the point is relative to the heading - but take the current
// angular velocity into account, too. The value is multiplied by two
// to avoid 'oversteering' - experimentally found.
float angle_2_point = theta - m_kart->getHeading()
- dt*m_kart->getBody()->getAngularVelocity().getY()*2.0f;
angle_2_point = normalizeAngle(angle_2_point);
if(fabsf(angle_2_point)<0.1) return 0.0f;
/** To understand this code, consider how a given steering angle determines
* the angle the kart is facing after one timestep:
* sin(steer_angle) = wheel_base / radius; --> compute radius of turn
* circumference = radius * 2 * M_PI; --> circumference of turn circle
* The kart drives dt*V units during a timestep of size dt. So the ratio
* of the driven distance to the circumference is the same as the angle
* the whole circle, or:
* angle / (2*M_PI) = dt*V / circumference
* Reversly, if the angle to drive to is given, the circumference can be
* computed, and from that the turn radius, and then the steer angle.
* (note: the 2*M_PI can be removed from the computations)
*/
float radius = dt*m_kart->getSpeed()/angle_2_point;
float sin_steer_angle = m_kart->getKartProperties()->getWheelBase()/radius;
#ifdef DEBUG_OUTPUT
printf("theta %f a2p %f angularv %f radius %f ssa %f\n",
theta, angle_2_point, m_body->getAngularVelocity().getY(),
radius, sin_steer_angle);
#endif
// Add 0.1 since rouding errors will otherwise result in the kart
// not using drifting.
if(sin_steer_angle <= -1.0f)
return -m_kart->getMaxSteerAngle()*m_skidding_threshold-0.1f;
if(sin_steer_angle >= 1.0f)
return m_kart->getMaxSteerAngle()*m_skidding_threshold+0.1f;
float steer_angle = asin(sin_steer_angle);
return steer_angle;
} // steerToPoint
//-----------------------------------------------------------------------------
void DefaultAIController::checkCrashes( const int STEPS, const Vec3& pos )
{
@ -857,7 +792,7 @@ void DefaultAIController::checkCrashes( const int STEPS, const Vec3& pos )
//Protection against having vel_normal with nan values
const Vec3 &VEL = m_kart->getVelocity();
Vec3 vel_normal(VEL.getX(), VEL.getZ(), 0.0);
Vec3 vel_normal(VEL.getX(), 0.0, VEL.getZ());
float speed=vel_normal.length();
// If the velocity is zero, no sense in checking for crashes in time
if(speed==0) return;
@ -993,18 +928,6 @@ void DefaultAIController::reset()
} // reset
//-----------------------------------------------------------------------------
inline float DefaultAIController::normalizeAngle(float angle)
{
while( angle > 2*M_PI ) angle -= 2*M_PI;
while( angle < -2*M_PI ) angle += 2*M_PI;
if( angle > M_PI ) angle -= 2*M_PI;
else if( angle < -M_PI ) angle += 2*M_PI;
return angle;
}
//-----------------------------------------------------------------------------
/** calc_steps() divides the velocity vector by the lenght of the kart,
* and gets the number of steps to use for the sight line of the kart.
@ -1034,47 +957,6 @@ int DefaultAIController::calcSteps()
return steps;
} // calcSteps
//-----------------------------------------------------------------------------
/** Converts the steering angle to a lr steering in the range of -1 to 1.
* If the steering angle is too great, it will also trigger skidding. This
* function uses a 'time till full steer' value specifying the time it takes
* for the wheel to reach full left/right steering similar to player karts
* when using a digital input device. This is done to remove shaking of
* AI karts (which happens when the kart frequently changes the direction
* of a turn). The parameter is defined in the kart properties.
* \param angle Steering angle.
* \param dt Time step.
*/
void DefaultAIController::setSteering(float angle, float dt)
{
float steer_fraction = angle / m_kart->getMaxSteerAngle();
m_controls->m_drift = fabsf(steer_fraction)>=m_skidding_threshold;
if(m_kart->hasViewBlockedByPlunger()) m_controls->m_drift = false;
float old_steer = m_controls->m_steer;
if (steer_fraction > 1.0f) steer_fraction = 1.0f;
else if(steer_fraction < -1.0f) steer_fraction = -1.0f;
if(m_kart->hasViewBlockedByPlunger())
{
if (steer_fraction > 0.5f) steer_fraction = 0.5f;
else if(steer_fraction < -0.5f) steer_fraction = -0.5f;
}
// The AI has its own 'time full steer' value (which is the time
float max_steer_change = dt/m_kart->getKartProperties()->getTimeFullSteerAI();
if(old_steer < steer_fraction)
{
m_controls->m_steer = (old_steer+max_steer_change > steer_fraction)
? steer_fraction : old_steer+max_steer_change;
}
else
{
m_controls->m_steer = (old_steer-max_steer_change < steer_fraction)
? steer_fraction : old_steer-max_steer_change;
}
} // setSteering
//-----------------------------------------------------------------------------
/**FindCurve() gathers info about the closest sectors ahead: the curve
* angle, the direction of the next turn, and the optimal speed at which the

View File

@ -1,3 +1,5 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
@ -17,14 +19,10 @@
// along with this program; if not, write to the Free Software
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_DEFAULT_SI_CONTROLLER_HPP
#ifndef HEADER_DEFAULT_AI_CONTROLLER_HPP
#define HEADER_DEFAULT_AI_CONTROLLER_HPP
#include "karts/controller/controller.hpp"
//#include "karts/auto_kart.hpp"
//#include "modes/profile_world.hpp"
//#include "utils/vec3.hpp"
#include "karts/controller/ai_base_controller.hpp"
class Track;
class LinearWorld;
@ -38,7 +36,7 @@ namespace irr
}
}
class DefaultAIController : public Controller
class DefaultAIController : public AIBaseController
{
private:
enum FallbackTactic
@ -123,18 +121,11 @@ private:
float m_curve_target_speed;
float m_curve_angle;
/** Keep a pointer to the track to reduce calls */
Track *m_track;
/** Keep a pointer to world. */
LinearWorld *m_world;
/** The current node the kart is on. This can be different from the value
* in LinearWorld, since it takes the chosen path of the AI into account
* (e.g. the closest point in LinearWorld might be on a branch not
* chosen by the AI). */
int m_track_node;
/** The graph of qudas of this track. */
const QuadGraph *m_quad_graph;
/** Which of the successors of a node was selected by the AI. */
std::vector<int> m_successor_index;
@ -162,12 +153,6 @@ private:
* is targeting at. */
irr::scene::ISceneNode *m_debug_sphere;
/** The minimum steering angle at which the AI adds skidding. Lower values
* tend to improve the line the AI is driving. This is used to adjust for
* different AI levels.
*/
float m_skidding_threshold;
/*Functions called directly from update(). They all represent an action
*that can be done, and end up setting their respective m_controls
*variable, except handle_race_start() that isn't associated with any
@ -182,17 +167,13 @@ private:
void handleNitroAndZipper();
void computeNearestKarts();
/*Lower level functions not called directly from update()*/
float steerToAngle(const size_t SECTOR, const float ANGLE);
float steerToPoint(const Vec3 &point, float dt);
void checkCrashes(const int STEPS, const Vec3& pos);
void findNonCrashingPoint(Vec3 *result);
float normalizeAngle(float angle);
int calcSteps();
void setSteering(float angle, float dt);
void findCurve();
protected:
virtual unsigned int getNextSector(unsigned int index);
public:
DefaultAIController(Kart *kart);

View File

@ -1,7 +1,9 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
// Copyright (C) 2008 Joerg Henrichs
// Copyright (C) 2004-2010 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2010 Eduardo Hernandez Munoz
// Copyright (C) 2008-2010 Joerg Henrichs
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
@ -45,14 +47,8 @@
#include "utils/constants.hpp"
EndController::EndController(Kart *kart, StateManager::ActivePlayer *player)
: Controller(kart, player)
: AIBaseController(kart, player)
{
m_kart_length = m_kart->getKartProperties()->getKartModel()->getLength();
m_kart_width = m_kart->getKartProperties()->getKartModel()->getWidth();
m_world = dynamic_cast<LinearWorld*>(World::getWorld());
m_track = m_world->getTrack();
m_quad_graph = &m_track->getQuadGraph();
m_next_node_index.reserve(m_quad_graph->getNumNodes());
m_successor_index.reserve(m_quad_graph->getNumNodes());
@ -112,7 +108,7 @@ EndController::EndController(Kart *kart, StateManager::ActivePlayer *player)
m_max_handicap_accel = 1.0f;
m_min_steps = 2;
m_skidding_threshold = 1.3f;
setSkiddingFraction(1.3f);
#ifdef AI_DEBUG
m_debug_sphere = irr_driver->getSceneManager()->addSphereSceneNode(1);
@ -214,8 +210,7 @@ void EndController::handleSteering(float dt)
if( fabsf(m_world->getDistanceToCenterForKart( m_kart->getWorldKartId() )) >
0.5f* m_quad_graph->getNode(m_track_node).getPathWidth()+0.5f )
{
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter(),
dt );
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter());
#ifdef AI_DEBUG
m_debug_sphere->setPosition(m_quad_graph->getQuad(next).getCenter().toIrrVector());
@ -234,7 +229,7 @@ void EndController::handleSteering(float dt)
#ifdef AI_DEBUG
m_debug_sphere->setPosition(straight_point.toIrrVector());
#endif
steer_angle = steerToPoint(straight_point, dt);
steer_angle = steerToPoint(straight_point);
}
#ifdef AI_DEBUG
@ -293,77 +288,6 @@ void EndController::handleRescue(const float DELTA)
}
} // handleRescue
//-----------------------------------------------------------------------------
float EndController::steerToAngle(const size_t SECTOR, const float ANGLE)
{
float angle = m_quad_graph->getAngleToNext(SECTOR,
m_successor_index[SECTOR]);
//Desired angle minus current angle equals how many angles to turn
float steer_angle = angle - m_kart->getHeading();
if(m_kart->hasViewBlockedByPlunger())
steer_angle += ANGLE/5;
else
steer_angle += ANGLE;
steer_angle = normalizeAngle( steer_angle );
return steer_angle;
} // steerToAngle
//-----------------------------------------------------------------------------
/** Computes the steering angle to reach a certain point. Note that the
* steering angle depends on the velocity of the kart (simple setting the
* steering angle towards the angle the point has is not correct: a slower
* kart will obviously turn less in one time step than a faster kart).
* \param point Point to steer towards.
* \param dt Time step.
*/
float EndController::steerToPoint(const Vec3 &point, float dt)
{
// No sense steering if we are not driving.
if(m_kart->getSpeed()==0) return 0.0f;
const float dx = point.getX() - m_kart->getXYZ().getX();
const float dz = point.getZ() - m_kart->getXYZ().getZ();
/** Angle from the kart position to the point in world coordinates. */
float theta = atan2(dx, dz);
// Angle is the point is relative to the heading - but take the current
// angular velocity into account, too. The value is multiplied by two
// to avoid 'oversteering' - experimentally found.
float angle_2_point = theta - m_kart->getHeading()
- dt*m_kart->getBody()->getAngularVelocity().getY()*2.0f;
angle_2_point = normalizeAngle(angle_2_point);
if(fabsf(angle_2_point)<0.1) return 0.0f;
/** To understand this code, consider how a given steering angle determines
* the angle the kart is facing after one timestep:
* sin(steer_angle) = wheel_base / radius; --> compute radius of turn
* circumference = radius * 2 * M_PI; --> circumference of turn circle
* The kart drives dt*V units during a timestep of size dt. So the ratio
* of the driven distance to the circumference is the same as the angle
* the whole circle, or:
* angle / (2*M_PI) = dt*V / circumference
* Reversly, if the angle to drive to is given, the circumference can be
* computed, and from that the turn radius, and then the steer angle.
* (note: the 2*M_PI can be removed from the computations)
*/
float radius = dt*m_kart->getSpeed()/angle_2_point;
float sin_steer_angle = m_kart->getKartProperties()->getWheelBase()/radius;
#ifdef DEBUG_OUTPUT
printf("theta %f a2p %f angularv %f radius %f ssa %f\n",
theta, angle_2_point, m_body->getAngularVelocity().getY(),
radius, sin_steer_angle);
#endif
// Add 0.1 since rouding errors will otherwise result in the kart
// not using drifting.
if(sin_steer_angle <= -1.0f) return -m_kart->getMaxSteerAngle()*m_skidding_threshold-0.1f;
if(sin_steer_angle >= 1.0f) return m_kart->getMaxSteerAngle()*m_skidding_threshold+0.1f;
float steer_angle = asin(sin_steer_angle);
return steer_angle;
} // steerToPoint
//-----------------------------------------------------------------------------
/** Find the sector that at the longest distance from the kart, that can be
* driven to without crashing with the track, then find towards which of
@ -444,18 +368,6 @@ void EndController::reset()
} // reset
//-----------------------------------------------------------------------------
inline float EndController::normalizeAngle(float angle)
{
while( angle > 2*M_PI ) angle -= 2*M_PI;
while( angle < -2*M_PI ) angle += 2*M_PI;
if( angle > M_PI ) angle -= 2*M_PI;
else if( angle < -M_PI ) angle += 2*M_PI;
return angle;
}
//-----------------------------------------------------------------------------
/** calc_steps() divides the velocity vector by the lenght of the kart,
* and gets the number of steps to use for the sight line of the kart.
@ -485,47 +397,6 @@ int EndController::calcSteps()
return steps;
} // calcSteps
//-----------------------------------------------------------------------------
/** Converts the steering angle to a lr steering in the range of -1 to 1.
* If the steering angle is too great, it will also trigger skidding. This
* function uses a 'time till full steer' value specifying the time it takes
* for the wheel to reach full left/right steering similar to player karts
* when using a digital input device. This is done to remove shaking of
* AI karts (which happens when the kart frequently changes the direction
* of a turn). The parameter is defined in the kart properties.
* \param angle Steering angle.
* \param dt Time step.
*/
void EndController::setSteering(float angle, float dt)
{
float steer_fraction = angle / m_kart->getMaxSteerAngle();
m_controls->m_drift = fabsf(steer_fraction)>=m_skidding_threshold;
if(m_kart->hasViewBlockedByPlunger()) m_controls->m_drift = false;
float old_steer = m_controls->m_steer;
if (steer_fraction > 1.0f) steer_fraction = 1.0f;
else if(steer_fraction < -1.0f) steer_fraction = -1.0f;
if(m_kart->hasViewBlockedByPlunger())
{
if (steer_fraction > 0.5f) steer_fraction = 0.5f;
else if(steer_fraction < -0.5f) steer_fraction = -0.5f;
}
// The AI has its own 'time full steer' value (which is the time
float max_steer_change = dt/m_kart->getKartProperties()->getTimeFullSteerAI();
if(old_steer < steer_fraction)
{
m_controls->m_steer = (old_steer+max_steer_change > steer_fraction)
? steer_fraction : old_steer+max_steer_change;
}
else
{
m_controls->m_steer = (old_steer-max_steer_change < steer_fraction)
? steer_fraction : old_steer-max_steer_change;
}
} // setSteering
//-----------------------------------------------------------------------------
/**FindCurve() gathers info about the closest sectors ahead: the curve
* angle, the direction of the next turn, and the optimal speed at which the

View File

@ -1,6 +1,9 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
// Copyright (C) 2004-2010 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2010 Eduardo Hernandez Munoz
// Copyright (C) 2010 Joerg Henrichs
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
@ -16,16 +19,15 @@
// along with this program; if not, write to the Free Software
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_END_KART_HPP
#define HEADER_END_KART_HPP
#ifndef HEADER_END_CONTROLLER_HPP
#define HEADER_END_CONTROLLER_HPP
#include "karts/controller/controller.hpp"
#include "modes/profile_world.hpp"
#include "utils/vec3.hpp"
#include "karts/controller/ai_base_controller.hpp"
class Track;
class LinearWorld;
class QuadGraph;
class Track;
class Vec3;
namespace irr
{
@ -35,7 +37,7 @@ namespace irr
}
}
class EndController : public Controller
class EndController : public AIBaseController
{
private:
/** Stores the type of the previous controller. This is necessary so that
@ -64,18 +66,11 @@ private:
float m_curve_target_speed;
float m_curve_angle;
/** Keep a pointer to the track to reduce calls */
Track *m_track;
/** Keep a pointer to world. */
LinearWorld *m_world;
/** The current node the kart is on. This can be different from the value
* in LinearWorld, since it takes the chosen path of the AI into account
* (e.g. the closest point in LinearWorld might be on a branch not
* chosen by the AI). */
int m_track_node;
/** The graph of qudas of this track. */
const QuadGraph *m_quad_graph;
/** Which of the successors of a node was selected by the AI. */
std::vector<int> m_successor_index;
@ -93,22 +88,10 @@ private:
int m_start_kart_crash_direction; //-1 = left, 1 = right, 0 = no crash.
/** Length of the kart, storing it here saves many function calls. */
float m_kart_length;
/** Cache width of kart. */
float m_kart_width;
/** For debugging purpose: a sphere indicating where the AI
* is targeting at. */
irr::scene::ISceneNode *m_debug_sphere;
/** The minimum steering angle at which the AI adds skidding. Lower values
* tend to improve the line the AI is driving. This is used to adjust for
* different AI levels.
*/
float m_skidding_threshold;
/*Functions called directly from update(). They all represent an action
*that can be done, and end up setting their respective m_controls
*variable, except handle_race_start() that isn't associated with any
@ -118,15 +101,10 @@ private:
void handleSteering(float dt);
void handleRescue(const float DELTA);
void handleBraking();
/*Lower level functions not called directly from update()*/
float steerToAngle(const size_t SECTOR, const float ANGLE);
float steerToPoint(const Vec3 &point, float dt);
void checkCrashes(const int STEPS, const Vec3& pos);
void findNonCrashingPoint(Vec3 *result);
float normalizeAngle(float angle);
int calcSteps();
void setSteering(float angle, float dt);
void findCurve();
public:
EndController(Kart *kart, StateManager::ActivePlayer* player);

View File

@ -1,7 +1,9 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
// Copyright (C) 2008 Joerg Henrichs
// Copyright (C) 2004-2010 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2010 Eduardo Hernandez Munoz
// Copyright (C) 2008-2010 Joerg Henrichs
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
@ -20,7 +22,7 @@
//The AI debugging works best with just 1 AI kart, so set the number of karts
//to 2 in main.cpp with quickstart and run supertuxkart with the arg -N.
#undef AI_DEBUG
#define AI_DEBUG
#include "karts/controller/new_ai_controller.hpp"
@ -44,14 +46,8 @@
#include "tracks/track.hpp"
#include "utils/constants.hpp"
NewAIController::NewAIController(Kart *kart) : Controller(kart)
NewAIController::NewAIController(Kart *kart) : AIBaseController(kart)
{
m_kart = kart;
m_kart_length = m_kart->getKartProperties()->getKartModel()->getLength();
m_kart_width = m_kart->getKartProperties()->getKartModel()->getWidth();
m_world = dynamic_cast<LinearWorld*>(World::getWorld());
m_track = m_world->getTrack();
m_quad_graph = &m_track->getQuadGraph();
m_next_node_index.reserve(m_quad_graph->getNumNodes());
m_successor_index.reserve(m_quad_graph->getNumNodes());
@ -116,9 +112,9 @@ NewAIController::NewAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_TEN_SECONDS;
m_max_start_delay = 0.5f;
m_min_steps = 0;
m_skidding_threshold = 4.0f;
m_nitro_level = NITRO_NONE;
m_handle_bomb = false;
setSkiddingFraction(4.0f);
break;
case RaceManager::RD_MEDIUM:
m_wait_for_players = true;
@ -130,9 +126,9 @@ NewAIController::NewAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_CALCULATE;
m_max_start_delay = 0.4f;
m_min_steps = 1;
m_skidding_threshold = 2.0f;
m_nitro_level = NITRO_SOME;
m_handle_bomb = true;
setSkiddingFraction(3.0f);
break;
case RaceManager::RD_HARD:
m_wait_for_players = false;
@ -141,9 +137,9 @@ NewAIController::NewAIController(Kart *kart) : Controller(kart)
m_item_tactic = IT_CALCULATE;
m_max_start_delay = 0.1f;
m_min_steps = 2;
m_skidding_threshold = 1.3f;
m_nitro_level = NITRO_ALL;
m_handle_bomb = true;
setSkiddingFraction(2.0f);
break;
}
@ -167,6 +163,16 @@ NewAIController::~NewAIController()
#endif
} // ~NewAIController
//-----------------------------------------------------------------------------
/** Returns the pre-computed successor of a graph node.
* \parameter index The index of the graph node for which the successor
* is searched.
*/
unsigned int NewAIController::getNextSector(unsigned int index)
{
return m_successor_index[index];
} // getNextSector
//-----------------------------------------------------------------------------
//TODO: if the AI is crashing constantly, make it move backwards in a straight
//line, then move forward while turning.
@ -238,8 +244,7 @@ void NewAIController::update(float dt)
/ (m_kart->getSpeed()-m_kart_ahead->getSpeed());
target += m_kart_ahead->getVelocity()*time_till_hit;
}
float steer_angle = steerToPoint(m_kart_ahead->getXYZ(),
dt);
float steer_angle = steerToPoint(m_kart_ahead->getXYZ());
setSteering(steer_angle, dt);
commands_set = true;
}
@ -366,8 +371,7 @@ void NewAIController::handleSteering(float dt)
if( fabsf(m_world->getDistanceToCenterForKart( m_kart->getWorldKartId() )) >
0.5f* m_quad_graph->getNode(m_track_node).getPathWidth()+1.0f )
{
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter(),
dt );
steer_angle = steerToPoint(m_quad_graph->getQuad(next).getCenter());
#ifdef AI_DEBUG
m_debug_sphere->setPosition(m_quad_graph->getQuad(next).getCenter().toIrrVector());
@ -758,76 +762,6 @@ void NewAIController::handleNitroAndZipper()
} // handleNitroAndZipper
//-----------------------------------------------------------------------------
float NewAIController::steerToAngle(const size_t SECTOR, const float ANGLE)
{
float angle = m_quad_graph->getAngleToNext(SECTOR,
m_successor_index[SECTOR]);
//Desired angle minus current angle equals how many angles to turn
float steer_angle = angle - m_kart->getHeading();
if(m_kart->hasViewBlockedByPlunger())
steer_angle += ANGLE/5;
else
steer_angle += ANGLE;
steer_angle = normalizeAngle( steer_angle );
return steer_angle;
} // steerToAngle
//-----------------------------------------------------------------------------
/** Computes the steering angle to reach a certain point. Note that the
* steering angle depends on the velocity of the kart (simple setting the
* steering angle towards the angle the point has is not correct: a slower
* kart will obviously turn less in one time step than a faster kart).
* \param point Point to steer towards.
* \param dt Time step.
*/
float NewAIController::steerToPoint(const Vec3 &point, float dt)
{
// No sense steering if we are not driving.
if(m_kart->getSpeed()==0) return 0.0f;
const float dx = point.getX() - m_kart->getXYZ().getX();
const float dz = point.getZ() - m_kart->getXYZ().getZ();
/** Angle from the kart position to the point in world coordinates. */
float theta = atan2(dx, dz);
// Angle is the point is relative to the heading - but take the current
// angular velocity into account, too. The value is multiplied by two
// to avoid 'oversteering' - experimentally found.
float angle_2_point = theta - m_kart->getHeading()
- dt*m_kart->getBody()->getAngularVelocity().getY()*2.0f;
angle_2_point = normalizeAngle(angle_2_point);
if(fabsf(angle_2_point)<0.1) return 0.0f;
/** To understand this code, consider how a given steering angle determines
* the angle the kart is facing after one timestep:
* sin(steer_angle) = wheel_base / radius; --> compute radius of turn
* circumference = radius * 2 * M_PI; --> circumference of turn circle
* The kart drives dt*V units during a timestep of size dt. So the ratio
* of the driven distance to the circumference is the same as the angle
* the whole circle, or:
* angle / (2*M_PI) = dt*V / circumference
* Reversly, if the angle to drive to is given, the circumference can be
* computed, and from that the turn radius, and then the steer angle.
* (note: the 2*M_PI can be removed from the computations)
*/
float radius = dt*m_kart->getSpeed()/angle_2_point;
float sin_steer_angle = m_kart->getKartProperties()->getWheelBase()/radius;
#ifdef DEBUG_OUTPUT
printf("theta %f a2p %f angularv %f radius %f ssa %f\n",
theta, angle_2_point, m_body->getAngularVelocity().getY(),
radius, sin_steer_angle);
#endif
// Add 0.1 since rouding errors will otherwise result in the kart
// not using drifting.
if(sin_steer_angle <= -1.0f) return -m_kart->getMaxSteerAngle()*m_skidding_threshold-0.1f;
if(sin_steer_angle >= 1.0f) return m_kart->getMaxSteerAngle()*m_skidding_threshold+0.1f;
float steer_angle = asin(sin_steer_angle);
return steer_angle;
} // steerToPoint
//-----------------------------------------------------------------------------
void NewAIController::checkCrashes( const int STEPS, const Vec3& pos )
{
@ -842,7 +776,7 @@ void NewAIController::checkCrashes( const int STEPS, const Vec3& pos )
//Protection against having vel_normal with nan values
const Vec3 &VEL = m_kart->getVelocity();
Vec3 vel_normal(VEL.getX(), VEL.getY(), 0.0);
Vec3 vel_normal(VEL.getX(), 0.0, VEL.getZ());
float speed=vel_normal.length();
// If the velocity is zero, no sense in checking for crashes in time
if(speed==0) return;
@ -867,7 +801,7 @@ void NewAIController::checkCrashes( const int STEPS, const Vec3& pos )
if(kart==m_kart||kart->isEliminated()) continue; // ignore eliminated karts
const Kart *other_kart = m_world->getKart(j);
// Ignore karts ahead that are faster than this kart.
if(m_kart->getVelocityLC().getY() < other_kart->getVelocityLC().getY())
if(m_kart->getVelocityLC().getZ() < other_kart->getVelocityLC().getZ())
continue;
Vec3 other_kart_xyz = other_kart->getXYZ() + other_kart->getVelocity()*(i*dt);
float kart_distance = (step_coord - other_kart_xyz).length_2d();
@ -894,22 +828,24 @@ void NewAIController::checkCrashes( const int STEPS, const Vec3& pos )
//-----------------------------------------------------------------------------
float NewAIController::findNonCrashingAngle()
{
unsigned int current_sector = m_track_node;
unsigned int current_sector = m_next_node_index[m_track_node];
const Vec3 &xyz = m_kart->getXYZ();
const Quad &q = m_quad_graph->getQuad(current_sector);
const Vec3 &right = q[2];
const Vec3 &left = q[3];
Vec3 final_right = q[2];
Vec3 final_left = q[3];
Vec3 final_right = q[2];
Vec3 final_left = q[3];
float very_right = -atan2(right.getX()-xyz.getX(),
right.getY()-xyz.getY())
- m_kart->getHeading();
right.getZ()-xyz.getZ())
;//- m_kart->getHeading();
float very_left = -atan2(left.getX()-xyz.getX(),
left.getY()-xyz.getY())
- m_kart->getHeading();
left.getZ()-xyz.getZ())
;//- m_kart->getHeading();
very_left = normalizeAngle(very_left);
very_right = normalizeAngle(very_right);
if(very_left<very_right)
printf("X\n");
float dist = 0;
while(dist<40.0f)
@ -919,17 +855,25 @@ float NewAIController::findNonCrashingAngle()
const Vec3 &left = q[3];
float angle_right = -atan2(right.getX()-xyz.getX(),
right.getY()-xyz.getY())
- m_kart->getHeading();
right.getZ()-xyz.getZ())
;//- m_kart->getHeading();
float angle_left = -atan2(left.getX()-xyz.getX(),
left.getY()-xyz.getY())
- m_kart->getHeading();
left.getZ()-xyz.getZ())
;//- m_kart->getHeading();
angle_left = normalizeAngle(angle_left);
angle_right = normalizeAngle(angle_right);
// Break if the left and the right beam overlap.
printf("dist %f vl %f al %f ar %f vr %f\n",
dist, very_left, angle_left, angle_right,
very_right);
if(angle_left<very_right ||
angle_right>very_left) break;
angle_right>very_left)
{
if(dist<0.1)
break;
break;
}
if(angle_left <very_left )
{
@ -946,7 +890,7 @@ float NewAIController::findNonCrashingAngle()
current_sector = m_next_node_index[current_sector];
}
Vec3 middle=(final_left+final_right)*0.5f;
float steer_angle=steerToPoint(middle, 1/60.0f);
float steer_angle=steerToPoint(middle);
#ifdef AI_DEBUG
m_debug_left->setPosition(final_left.toIrrVector());
m_debug_right->setPosition(final_right.toIrrVector());
@ -1040,18 +984,6 @@ void NewAIController::reset()
} // reset
//-----------------------------------------------------------------------------
inline float NewAIController::normalizeAngle(float angle)
{
while( angle > 2*M_PI ) angle -= 2*M_PI;
while( angle < -2*M_PI ) angle += 2*M_PI;
if( angle > M_PI ) angle -= 2*M_PI;
else if( angle < -M_PI ) angle += 2*M_PI;
return angle;
}
//-----------------------------------------------------------------------------
/** calc_steps() divides the velocity vector by the lenght of the kart,
* and gets the number of steps to use for the sight line of the kart.
@ -1059,7 +991,7 @@ inline float NewAIController::normalizeAngle(float angle)
*/
int NewAIController::calcSteps()
{
int steps = int( m_kart->getVelocityLC().getY() / m_kart_length );
int steps = int( m_kart->getVelocityLC().getZ() / m_kart_length );
if( steps < m_min_steps ) steps = m_min_steps;
//Increase the steps depending on the width, if we steering hard,
@ -1081,47 +1013,6 @@ int NewAIController::calcSteps()
return steps;
} // calcSteps
//-----------------------------------------------------------------------------
/** Converts the steering angle to a lr steering in the range of -1 to 1.
* If the steering angle is too great, it will also trigger skidding. This
* function uses a 'time till full steer' value specifying the time it takes
* for the wheel to reach full left/right steering similar to player karts
* when using a digital input device. This is done to remove shaking of
* AI karts (which happens when the kart frequently changes the direction
* of a turn). The parameter is defined in the kart properties.
* \param angle Steering angle.
* \param dt Time step.
*/
void NewAIController::setSteering(float angle, float dt)
{
float steer_fraction = angle / m_kart->getMaxSteerAngle();
m_controls->m_drift = fabsf(steer_fraction)>=m_skidding_threshold;
if(m_kart->hasViewBlockedByPlunger()) m_controls->m_drift = false;
float old_steer = m_controls->m_steer;
if (steer_fraction > 1.0f) steer_fraction = 1.0f;
else if(steer_fraction < -1.0f) steer_fraction = -1.0f;
if(m_kart->hasViewBlockedByPlunger())
{
if (steer_fraction > 0.5f) steer_fraction = 0.5f;
else if(steer_fraction < -0.5f) steer_fraction = -0.5f;
}
// The AI has its own 'time full steer' value (which is the time
float max_steer_change = dt/m_kart->getKartProperties()->getTimeFullSteerAI();
if(old_steer < steer_fraction)
{
m_controls->m_steer = (old_steer+max_steer_change > steer_fraction)
? steer_fraction : old_steer+max_steer_change;
}
else
{
m_controls->m_steer = (old_steer-max_steer_change < steer_fraction)
? steer_fraction : old_steer-max_steer_change;
}
} // setSteering
//-----------------------------------------------------------------------------
/**FindCurve() gathers info about the closest sectors ahead: the curve
* angle, the direction of the next turn, and the optimal speed at which the
@ -1133,7 +1024,7 @@ void NewAIController::findCurve()
{
float total_dist = 0.0f;
int i;
for(i = m_track_node; total_dist < m_kart->getVelocityLC().getY();
for(i = m_track_node; total_dist < m_kart->getVelocityLC().getZ();
i = m_next_node_index[i])
{
total_dist += m_quad_graph->getDistanceToNext(i, m_successor_index[i]);

View File

@ -1,3 +1,5 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2004-2005 Steve Baker <sjbaker1@airmail.net>
// Copyright (C) 2006-2007 Eduardo Hernandez Munoz
@ -16,10 +18,10 @@
// along with this program; if not, write to the Free Software
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_NEWAI_CONTROLLER_HPP
#define HEADER_NEWAI_CONTROLLER_HPP
#ifndef HEADER_NEW_AI_CONTROLLER_HPP
#define HEADER_NEW_AI_CONTROLLER_HPP
#include "karts/controller/controller.hpp"
#include "karts/controller/ai_base_controller.hpp"
#include "utils/vec3.hpp"
/* third coord won't be used */
@ -35,7 +37,7 @@ namespace irr
}
}
class NewAIController : public Controller
class NewAIController : public AIBaseController
{
private:
enum FallbackTactic
@ -120,18 +122,11 @@ private:
float m_curve_target_speed;
float m_curve_angle;
/** Keep a pointer to the track to reduce calls */
Track *m_track;
/** Keep a pointer to world. */
LinearWorld *m_world;
/** The current node the kart is on. This can be different from the value
* in LinearWorld, since it takes the chosen path of the AI into account
* (e.g. the closest point in LinearWorld might be on a branch not
* chosen by the AI). */
int m_track_node;
/** The graph of qudas of this track. */
const QuadGraph *m_quad_graph;
/** Which of the successors of a node was selected by the AI. */
std::vector<int> m_successor_index;
@ -149,23 +144,11 @@ private:
int m_start_kart_crash_direction; //-1 = left, 1 = right, 0 = no crash.
/** Length of the kart, storing it here saves many function calls. */
float m_kart_length;
/** Cache width of kart. */
float m_kart_width;
/** For debugging purpose: a sphere indicating where the AI
* is targeting at. */
irr::scene::ISceneNode *m_debug_sphere;
irr::scene::ISceneNode *m_debug_left, *m_debug_right;
/** The minimum steering angle at which the AI adds skidding. Lower values
* tend to improve the line the AI is driving. This is used to adjust for
* different AI levels.
*/
float m_skidding_threshold;
/*Functions called directly from update(). They all represent an action
*that can be done, and end up setting their respective m_controls
*variable, except handle_race_start() that isn't associated with any
@ -179,19 +162,14 @@ private:
void handleBraking();
void handleNitroAndZipper();
void computeNearestKarts();
/*Lower level functions not called directly from update()*/
float steerToAngle(const size_t SECTOR, const float ANGLE);
float steerToPoint(const Vec3 &point, float dt);
void checkCrashes(const int STEPS, const Vec3& pos);
void findNonCrashingPoint(Vec3 *result);
float findNonCrashingAngle();
float normalizeAngle(float angle);
int calcSteps();
void setSteering(float angle, float dt);
void findCurve();
protected:
virtual unsigned int getNextSector(unsigned int index);
public:
NewAIController(Kart *kart);

View File

@ -232,6 +232,35 @@ void PlayerController::steer(float dt, int steer_val)
*/
void PlayerController::update(float dt)
{
#ifdef THIS_CAN_BE_REMOVED
m_controls->m_look_back = false;
m_controls->m_nitro = false;
static float min_x = 99999;
static float max_x = -99999;
static float min_z = 99999;
static float max_z = -99999;
const Vec3 &xyz = m_kart->getXYZ();
min_x = std::min(min_x, xyz.getX());
max_x = std::max(max_x, xyz.getX());
min_z = std::min(min_z, xyz.getZ());
max_z = std::max(max_z, xyz.getZ());
m_controls->m_accel = 1.0f;
m_controls->m_brake = false;
m_controls->m_steer = 1.0f;
printf("xyz %f %f %f hpr %f %f %f x %f %f y %f %f r %f %f\n",
m_kart->getXYZ().getX(),
m_kart->getXYZ().getY(),
m_kart->getXYZ().getZ(),
m_kart->getHeading(),
m_kart->getPitch(),
m_kart->getRoll(),
min_x, max_x, min_z, max_z,
0.5f*(max_x-min_x),
0.5f*(max_z-min_z)
);
return;
#endif
// Don't do steering if it's replay. In position only replay it doesn't
// matter, but if it's physics replay the gradual steering causes
// incorrect results, since the stored values are already adjusted.

View File

@ -35,7 +35,6 @@
#include "states_screens/race_gui.hpp"
#include "io/file_manager.hpp"
#include "items/projectile_manager.hpp"
#include "karts/auto_kart.hpp"
#include "karts/controller/default_ai_controller.hpp"
#include "karts/controller/new_ai_controller.hpp"
#include "karts/controller/player_controller.hpp"