Classes | Defines | Typedefs | Functions
utils.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  BELIEFSTATEWITHBINARYHVALS
struct  BINARYHIDDENVARIABLE
struct  bresenham_param_t
struct  POLICYBELIEFSTATEWITHBINARYHVALS
struct  sbpl_2Dcell_t
struct  sbpl_2Dpt_t

Defines

#define __max(x, y)   (x>y?x:y)
#define __min(x, y)   (x>y?y:x)
#define CONTXY2DISC(X, CELLSIZE)   (((X)>=0)?((int)((X)/(CELLSIZE))):((int)((X)/(CELLSIZE))-1))
#define DISCXY2CONT(X, CELLSIZE)   ((X)*(CELLSIZE) + (CELLSIZE)/2.0)
#define NORMALIZEDISCTHETA(THETA, THETADIRS)   (((THETA>=0)?((THETA)%(THETADIRS)):(((THETA)%(THETADIRS)+THETADIRS)%THETADIRS)))
#define PI_CONST   3.141592653589793238462643383279502884
#define UNKNOWN_COST   1000000

Typedefs

typedef struct
BELIEFSTATEWITHBINARYHVALS 
sbpl_BeliefStatewithBinaryh_t
typedef struct BINARYHIDDENVARIABLE sbpl_BinaryHiddenVar_t
typedef struct
POLICYBELIEFSTATEWITHBINARYHVALS 
sbpl_PolicyStatewithBinaryh_t

Functions

void CheckMDP (CMDP *mdp)
void computeDistancestoNonfreeAreas (unsigned char **Grid2D, int width_x, int height_y, unsigned char obsthresh, float **disttoObs_incells, float **disttoNonfree_incells)
 computes 8-connected distances - performs distance transform in two linear passes
double computeMinUnsignedAngleDiff (double angle1, double angle2)
 computes minimum unsigned difference between two angles in radians
int ComputeNumofStochasticActions (CMDP *pMDP)
int ContTheta2Disc (double fTheta, int NUMOFANGLEVALS)
 converts continuous (radians) version of angle into discrete
double DiscTheta2Cont (int nTheta, int NUMOFANGLEVALS)
 converts discretized version of angle into continuous (radians)
void EvaluatePolicy (CMDP *PolicyMDP, int StartStateID, int GoalStateID, double *PolValue, bool *bFullPolicy, double *Pcgoal, int *nMerges, bool *bCycles)
void get_bresenham_parameters (int p1x, int p1y, int p2x, int p2y, bresenham_param_t *params)
 one of the three functions that correspond to bresenham algorithm of path following this function computes bresenham parameters given the start and end points on the line segment
void get_current_point (bresenham_param_t *params, int *x, int *y)
 one of the three functions that correspond to bresenham algorithm of path following returns current cell on the line segment
int get_next_point (bresenham_param_t *params)
 one of the three functions that correspond to bresenham algorithm of path following moves to the next point
bool IsInsideFootprint (sbpl_2Dpt_t pt, vector< sbpl_2Dpt_t > *bounding_polygon)
 returns true if 2D point is within the specified polygon given by ordered sequence of 2D points (last point is automatically connected to the first)
double normalizeAngle (double angle)
void PrintMatrix (int **matrix, int rows, int cols, FILE *fOut)

Define Documentation

#define __max (   x,
 
)    (x>y?x:y)

Definition at line 33 of file utils.h.

#define __min (   x,
 
)    (x>y?y:x)

Definition at line 34 of file utils.h.

#define CONTXY2DISC (   X,
  CELLSIZE 
)    (((X)>=0)?((int)((X)/(CELLSIZE))):((int)((X)/(CELLSIZE))-1))

Definition at line 40 of file utils.h.

#define DISCXY2CONT (   X,
  CELLSIZE 
)    ((X)*(CELLSIZE) + (CELLSIZE)/2.0)

Definition at line 41 of file utils.h.

#define NORMALIZEDISCTHETA (   THETA,
  THETADIRS 
)    (((THETA>=0)?((THETA)%(THETADIRS)):(((THETA)%(THETADIRS)+THETADIRS)%THETADIRS)))

Definition at line 38 of file utils.h.

#define PI_CONST   3.141592653589793238462643383279502884

Definition at line 44 of file utils.h.

#define UNKNOWN_COST   1000000

Definition at line 46 of file utils.h.


Typedef Documentation


Function Documentation

void CheckMDP ( CMDP mdp)

Definition at line 104 of file utils.cpp.

void computeDistancestoNonfreeAreas ( unsigned char **  Grid2D,
int  width_x,
int  height_y,
unsigned char  obsthresh,
float **  disttoObs_incells,
float **  disttoNonfree_incells 
)

computes 8-connected distances - performs distance transform in two linear passes

Definition at line 543 of file utils.cpp.

double computeMinUnsignedAngleDiff ( double  angle1,
double  angle2 
)

computes minimum unsigned difference between two angles in radians

Definition at line 522 of file utils.cpp.

Definition at line 189 of file utils.cpp.

int ContTheta2Disc ( double  fTheta,
int  NUMOFANGLEVALS 
)

converts continuous (radians) version of angle into discrete

Note:
maps 0->0, [delta/2, 3/2*delta)->1, [3/2*delta, 5/2*delta)->2,...

Definition at line 443 of file utils.cpp.

double DiscTheta2Cont ( int  nTheta,
int  NUMOFANGLEVALS 
)

converts discretized version of angle into continuous (radians)

Note:
maps 0->0, 1->delta, 2->2*delta, ...

Definition at line 433 of file utils.cpp.

void EvaluatePolicy ( CMDP PolicyMDP,
int  StartStateID,
int  GoalStateID,
double *  PolValue,
bool *  bFullPolicy,
double *  Pcgoal,
int *  nMerges,
bool *  bCycles 
)

Definition at line 209 of file utils.cpp.

void get_bresenham_parameters ( int  p1x,
int  p1y,
int  p2x,
int  p2y,
bresenham_param_t params 
)

one of the three functions that correspond to bresenham algorithm of path following this function computes bresenham parameters given the start and end points on the line segment

Definition at line 347 of file utils.cpp.

void get_current_point ( bresenham_param_t params,
int *  x,
int *  y 
)

one of the three functions that correspond to bresenham algorithm of path following returns current cell on the line segment

Definition at line 394 of file utils.cpp.

int get_next_point ( bresenham_param_t params)

one of the three functions that correspond to bresenham algorithm of path following moves to the next point

Definition at line 412 of file utils.cpp.

bool IsInsideFootprint ( sbpl_2Dpt_t  pt,
vector< sbpl_2Dpt_t > *  bounding_polygon 
)

returns true if 2D point is within the specified polygon given by ordered sequence of 2D points (last point is automatically connected to the first)

Definition at line 484 of file utils.cpp.

double normalizeAngle ( double  angle)
Note:
counterclockwise is positive
Parameters:
angleinput angle should be in radians
Returns:
output is an angle in the range of from 0 to 2*PI

Definition at line 457 of file utils.cpp.

void PrintMatrix ( int **  matrix,
int  rows,
int  cols,
FILE *  fOut 
)

Definition at line 115 of file utils.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


sbpl
Author(s): Maxim Likhachev/maximl@seas.upenn.edu
autogenerated on Fri Jan 18 2013 13:41:53