#include <math.h>
#include <stdlib.h>
Include dependency graph for Common.h:
This graph shows which files directly or indirectly include this file:
Go to the source code of this file.
constants for some often used angles | |
const double | pi = 3.1415926535897932384626433832795 |
constant for a half circle | |
const double | pi2 = 2.0*3.1415926535897932384626433832795 |
constant for a full circle | |
const double | pi3_2 = 1.5*3.1415926535897932384626433832795 |
constant for three quater circle | |
const double | pi_2 = 0.5*3.1415926535897932384626433832795 |
constant for a quarter circle | |
const double | pi_180 = 3.1415926535897932384626433832795/180 |
constant for a 1 degree | |
const double | pi_4 = 3.1415926535897932384626433832795*0.25 |
constant for a 1/8 circle | |
const double | pi3_4 = 3.1415926535897932384626433832795*0.75 |
constant for a 3/8 circle | |
constant for bayesian filter | |
const double | e = 2.71828182845902353602874713527 |
constant for e | |
Defines | |
#define | max(a, b) (((a) > (b)) ? (a) : (b)) |
defines the maximum of a and b | |
#define | min(a, b) (((a) < (b)) ? (a) : (b)) |
defines the minimum of a and b | |
#define | sgn(a) ( (a) < 0 ? -1 : ((a)==0) ? 0 : 1 ) |
defines the sign of a | |
#define | sqr(a) ( (a) * (a) ) |
defines the square of a value | |
Functions | |
double | sec (const double a) |
double | cosec (const double a) |
long | toMicroRad (double angle) |
Converts angle from rad to long in microrad. | |
double | fromMicroRad (long microrad) |
Converts angle long in microrad to rad. | |
double | toDegrees (double angle) |
Converts angle from rad to degrees. | |
double | fromDegrees (double degrees) |
Converts angle from degrees to rad. | |
double | normalize (double data) |
reduce angle to [-pi..+pi] | |
double | random () |
The function returns a random number in the range of [0..1]. | |
int | random (int n) |
The function returns a random integer number in the range of [0..n-1]. |
Max Risler
Definition in file Common.h.
|
|
|
defines the sign of a
Definition at line 37 of file Common.h. Referenced by OCBridge::addPercept(), BitePoint::addPercept(), GT2004HeadControl::calculateClosestLandmark(), ObservationTable< 280, 200, 25 >::create(), GT2004ImageProcessor::scan(), OpenChallengeSymbols::update(), and GT2004MotionControl::wagTail(). |
|
|
Definition at line 47 of file Common.h. Referenced by GT2004BasicBehaviorNextGT2004ParametersToBeMeasured::execute(), and QueueFillRequest::QueueFillRequest(). |
|
|
|
Converts angle from rad to long in microrad. Robot uses long microrad for joint angles.
Definition at line 80 of file Common.h. Referenced by InvKinWalkingEngine::calculateData(), GT2004WalkingEngine::calculateData(), DebugMotionControl::clip(), SimpleMotionRecognition::getAngleYZ(), SimpleMotionRecognition::headIsNotInMotion(), GT2004HeadPathPlanner::headPositionReached(), GT2004HeadControl::setJointsDirect(), and GT2004MotionControl::wagTail(). |
|
Converts angle long in microrad to rad.
Definition at line 87 of file Common.h. Referenced by GT2004SensorDataProcessor::buildCameraMatrix(), GT2004SensorDataProcessor::buildPSDPercept(), Kinematics::calcAbsRoll(), Kinematics::calcHeadHeight(), BB2004Calibrator::evolve(), GT2004BasicBehaviorDogAsJoystick::execute(), GT2004SensorDataProcessor::getCameraVelocity(), Kinematics::getRelativeRobotVertices(), OpenChallengeSymbols::getSensorAccelerationX(), OpenChallengeSymbols::getSensorAccelerationY(), OpenChallengeSymbols::getSensorAccelerationZ(), and OpenChallengeSymbols::update(). |
|
|
Converts angle from degrees to rad.
Definition at line 100 of file Common.h. References pi_180. Referenced by AngleSymbols::calculateCombinedAngles(), RobotPoseSymbols::computeGoalieDefendMinPos(), GT2004BasicBehaviorGoToPoint::execute(), GT2004BasicBehaviorGoForwardToPoint::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoaliePositionReturn::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004PotentialFieldBasicBehaviorGoToPose::execute(), GT2004BasicBehaviorEvolveOmniParameters::execute(), BasicBehaviorStand::execute(), BasicBehaviorWalk::execute(), MathFunctions::getCos(), MathFunctions::getNormalize(), MotionRecognition::getRobotRotationFromBounce(), MathFunctions::getSin(), GTStandardConverter::load(), WalkAccelerationRestrictor::restrictAccelerations(), KickSelectionTable::retrieveKick(), GoalRecognizer::scanLinesForGoals(), GT2004GoalRecognizer::scanLinesForGoals(), OpenChallengeSymbols::update(), GT2004ConfigurationSymbols::update(), ObstaclesSymbols::update(), and RobotPoseSymbols::updateGoalieDefendPosition(). |
|
reduce angle to [-pi..+pi]
Definition at line 107 of file Common.h. Referenced by GT2004ObstaclesLocator::addObstaclePoint(), GT2004ObstaclesLocator::addObstaclePoints(), GT2004ObstaclesLocator::addPSDPercept(), GT2004HeadControl::beginBallSearchAt(), GT2004ImageProcessor::calcEdgeAngle(), GT2004HeadControl::calculateClosestLandmark(), AngleSymbols::calculateCombinedAngles(), GT2004ObstaclesLocator::determineNextFreeTeammate(), GT2004StrategySymbols::estimateTimeToReachBall(), GT2004ImageProcessor::execute(), GT2004BasicBehaviorGoToPoint::execute(), GT2004BasicBehaviorGoaliePositionReturn::execute(), GT2004BasicBehaviorEvolveOmniParameters::execute(), GT2004ImageProcessor::filterLinesPercept(), AngleSymbols::getAngleToCenterOfField(), BallSymbols::getAngleToOpponentGoal(), AngleSymbols::getAngleToOpponentGoal(), AngleSymbols::getAngleToPointBehindOpponentGoal(), AngleSymbols::getBestAngleAwayFromOwnGoal(), AngleSymbols::getBestAngleAwayFromOwnGoalNoObstacles(), AngleSymbols::getBestAngleToOpponentGoal(), AngleSymbols::getBestAngleToOpponentGoalNoObstacles(), Field::getClosestPoint(), AngleSymbols::getGoalieGoalKickAngle(), MathFunctions::getNormalize(), ObstaclesModel::getSectorFromAngle(), GT2004BallLocator::handleSeenBall(), Pose2D::operator+=(), GT2004BehaviorControl::postExecute(), KickSelectionTable::retrieveKick(), and Parcour::update(). |
|
The function returns a random number in the range of [0..1].
Definition at line 126 of file Common.h. Referenced by Individual::crossingOverOf(), Population< GT2004Parameters, 10 >::evolve(), GT2004SelfLocator::execute(), BBInvKinIndividual::extrapolate(), CalibrationIndividual::extrapolate(), BBInvKinIndividual::interpolate(), CalibrationIndividual::interpolate(), BBInvKinIndividual::mutate(), CalibrationIndividual::mutate(), Individual::mutationOf(), Pose2D::random(), random(), GT2004SelfLocator::resample(), TemplateTable< 50000 >::sample(), and GT2004SelfLocator::updateByOdometry(). |
|
The function returns a random integer number in the range of [0..n-1].
Definition at line 133 of file Common.h. References random(). |
Here is the call graph for this function:
|
constant for a half circle
Definition at line 54 of file Common.h. Referenced by GT2004ImageProcessor::calcEdgeAngle(), Kinematics::calcHeadHeight(), AngleSymbols::calculateCombinedAngles(), GT2004ParametersSet::calculateMergedParameterSet(), InvKinWalkingEngine::calculateRelativeFootPosition(), GT2004WalkingEngine::calculateRelativeFootPosition(), ChallengeSymbols::challenge2OptimalRotation(), RandomMotionGenerator::computeDirection(), ConditionalBoundary::ConditionalBoundary(), TemplateTable< 50000 >::create(), BoxSpecialist::detectFreePartOfGoal(), ObstacleAvoiderOnGreenFieldERS7::execute(), ObstacleAvoiderOnGreenField::execute(), GT2004ImageProcessor::execute(), GT2004BasicBehaviorGoToPointAndAvoidObstacles::execute(), GT2004BasicBehaviorTurnAroundPoint::execute(), GT2004BasicBehaviorGoToBall::execute(), GT2004PotentialFieldBasicBehaviorGoToPose::execute(), GT2004BasicBehaviorNextGT2004ParametersToBeMeasured::execute(), GT2004BasicBehaviorMeasureGT2004ParametersBlind::execute(), PotentialfieldAStarNode::expand(), GT2004ImageProcessor::filterPercepts(), ObstaclesModel::getAngleOfSector(), CheckerboardDetector::getPositionFromAngles(), GT2004ParametersSet::getRatio(), ObstaclesModel::getSectorFromAngle(), ForwardTurningParcour::getTargetPose(), GT2004BasicBehaviorEvolveOmniParameters::GT2004BasicBehaviorEvolveOmniParameters(), GT2004BasicBehaviorGoToPointAndAvoidObstacles::GT2004BasicBehaviorGoToPointAndAvoidObstacles(), GT2004EdgeSpecialist::GT2004EdgeSpecialist(), GT2004ImageProcessor::GT2004ImageProcessor(), GT2004HeadPathPlanner::headPositionReached(), intersectCircleAndCircle(), KalmanConstantSpeedModel::KalmanConstantSpeedModel(), FourierCoefficient::merge(), Individual::mutationOf(), normalize(), PfPose::normRotation(), ObstacleAvoiderOnGreenField::ObstacleAvoiderOnGreenField(), ObstacleAvoiderOnGreenFieldERS7::ObstacleAvoiderOnGreenFieldERS7(), GT2004SelfLocator::poseFromBearings(), GT2004SelfLocator::poseFromBearingsAndDistance(), RandomMotionGenerator::RandomMotionGenerator(), Field::randomPose(), KickSelectionTable::retrieveKick(), TemplateTable< 50000 >::sample(), GT2004ParametersSet::setRatio(), GT2004ParametersSet::setSpeed(), SpecialPerceptSelfLocator::SpecialPerceptSelfLocator(), toDegrees(), EvolutionSymbols::update(), GT2004SelfLocator::updateByFlag(), GT2004SelfLocator::updateByGoalPost(), GT2004SelfLocator::updateByPoint(), and GT2004MotionControl::wagTail(). |
|
constant for a full circle
Definition at line 56 of file Common.h. Referenced by GT2004ImageProcessor::calcEdgeAngle(), GT2004SelfLocator::calcPose(), FourierCoefficient::calculate(), AngleSymbols::calculateCombinedAngles(), RBallSpecialist2::calculateLargeCircle(), AngleSymbols::calculateLocalisationBasedAngles(), RandomMotionGenerator::computeDirection(), PotentialfieldAStarNode::computeHeuristicBetween(), Image::convertFromYCbCrToHSI(), GT2004StrategySymbols::estimateTimeToReachBall(), PotentialfieldAStarNode::expand(), FourierCoefficient::fourierSynth(), ObstaclesModel::getAngleOfNextFreeSector(), ObstaclesModel::getAngleOfNextFreeSectorLeft(), ObstaclesModel::getAngleOfNextFreeSectorRight(), ObstaclesModel::getAngleOfSector(), Field::getClosestPoint(), ObstaclesModel::getSectorFromAngle(), GT2004ObstaclesLocator::GT2004ObstaclesLocator(), FourierCoefficient::merge(), Individual::mutationOf(), normalize(), PfPose::normRotation(), Polygon::pointInside(), GT2004SelfLocator::poseFromBearings(), reduceToConvexHullByWrapping(), and KickSelectionTable::retrieveKick(). |
|
constant for three quater circle
|
|
constant for a quarter circle
Definition at line 60 of file Common.h. Referenced by OCBridge::addPercept(), BitePoint::addPercept(), GT2004ImageProcessor::calcEdgeAngle(), Geometry::calculateBallInImage(), ChallengeSymbols::challenge2OptimalRotation(), Object::computeAbsFieldVecAt(), CircleCalculation::cutMiddlePerpendiculars(), Field::getClosestPoint(), ObstaclesModel::getDistanceInCorridor(), CheckerboardDetector::getMiddleAndLengthOfPerpendicular(), GT2004ParametersSet::GT2004ParametersSet(), Kinematics::jointsFromLegPosition(), GT2004SelfLocator::poseFromBearingsAndDistance(), GT2004ObstaclesLocator::setObstaclesModel(), theta(), and ObstaclesSymbols::update(). |
|
constant for a 1 degree
Definition at line 62 of file Common.h. Referenced by fromDegrees(), and Parser::parseAngle(). |
|
constant for a 1/8 circle
Definition at line 64 of file Common.h. Referenced by GT2004BallSpecialist::addBallPercept(), GT2004BasicBehaviorNextGT2004ParametersToBeMeasured::execute(), ForwardTurningParcour::getTargetPose(), GT2004ParametersSet::GT2004ParametersSet(), ObstacleAvoiderOnGreenField::ObstacleAvoiderOnGreenField(), ObstacleAvoiderOnGreenFieldERS7::ObstacleAvoiderOnGreenFieldERS7(), and GaussBell::updateSigmasAndAngle(). |
|
constant for a 3/8 circle
|
|
constant for e
Definition at line 72 of file Common.h. Referenced by Kinematics::calcLegPosition(), slist< figure >::erase(), GT2004SelfLocator::execute(), invert2(), slist< T >::iterator::operator!=(), slist< T >::iterator::operator=(), and Xabsl2Engine::Xabsl2Engine(). |