The CollisionDetection class determines whether a given configuration q of the robot will result in a collision with the environment.  
 More...
#include <collisiondetection.h>
 | 
| 
  | CollisionDetection () | 
|   | Constructor. 
  | 
|   | 
| template<typename T >  | 
| bool  | isTraversable (const T *node) | 
|   | evaluates whether the configuration is safe  More...
  | 
|   | 
| float  | configurationCost (float x, float y, float t) | 
|   | Calculates the cost of the robot taking a specific configuration q int the World W.  More...
  | 
|   | 
| bool  | configurationTest (float x, float y, float t) | 
|   | Tests whether the configuration q of the robot is in C_free.  More...
  | 
|   | 
| 
void  | updateGrid (nav_msgs::OccupancyGrid::Ptr map) | 
|   | updates the grid with the world map 
  | 
|   | 
The CollisionDetection class determines whether a given configuration q of the robot will result in a collision with the environment. 
It is supposed to return a boolean value that returns true for collisions and false in the case of a safe node. 
 
  
  
      
        
          | float HybridAStar::CollisionDetection::configurationCost  | 
          ( | 
          float  | 
          x,  | 
         
        
           | 
           | 
          float  | 
          y,  | 
         
        
           | 
           | 
          float  | 
          t  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
inline   | 
  
 
Calculates the cost of the robot taking a specific configuration q int the World W. 
- Parameters
 - 
  
    | x | the x position  | 
    | y | the y position  | 
    | t | the theta angle  | 
  
   
- Returns
 - the cost of the configuration q of W(q) 
 
 
 
      
        
          | bool CollisionDetection::configurationTest  | 
          ( | 
          float  | 
          x,  | 
        
        
           | 
           | 
          float  | 
          y,  | 
        
        
           | 
           | 
          float  | 
          t  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Tests whether the configuration q of the robot is in C_free. 
- Parameters
 - 
  
    | x | the x position  | 
    | y | the y position  | 
    | t | the theta angle  | 
  
   
- Returns
 - true if it is in C_free, else false 
 
 
 
template<typename T > 
  
  
      
        
          | bool HybridAStar::CollisionDetection::isTraversable  | 
          ( | 
          const T *  | 
          node | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
evaluates whether the configuration is safe 
- Returns
 - true if it is traversable, else false 
 
 
 
The documentation for this class was generated from the following files: