libmove3d-planners
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Friends Macros Groups Pages
CollisionSpaceCell.hpp
1 /*
2  * CollisionSpaceCell.h
3  * BioMove3D
4  *
5  * Created by Jim Mainprice on 07/06/10.
6  * Copyright 2010 LAAS/CNRS. All rights reserved.
7  *
8  */
9 
10 #ifndef CELL_COLLISION_CHECKER_H_
11 #define CELL_COLLISION_CHECKER_H_
12 
13 #include "API/planningAPI.hpp"
14 #include "API/Grids/gridsAPI.hpp"
15 
17 {
18 public:
19  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
20 
21  CollisionSpaceCell(int i, const Eigen::Vector3d& corner, API::ThreeDGrid* grid);
22 
23  //setters and getters
24  inline bool isValid(void){return m_Valid;}
25  inline void setValid(bool value){m_Valid = value;}
26 
27  inline bool isVisited(void){return m_Visited;}
28  inline void setVisited(bool value){m_Visited = value;}
29 
30  inline bool isOccupied(void) {return m_Occupied;}
31  inline void setOccupied(bool value) {m_Occupied = value;}
32 
33  const Eigen::Vector3i& getLocation() { return m_Location; }
34 
35  void drawStatic();
36  void draw(int color, int width);
37  void draw(void);
38 
41  Eigen::Vector3i m_ClosestPoint;
43 private:
44 
45  std::vector<Edge*> _edges;
46  std::vector<Node*> _nodes;
47 
48  bool m_Valid; //There is no static obstacles crossing this cell
49  bool m_Visited;
50  bool m_Occupied;
51 
52  Eigen::Vector3d _cellSize;
53  Eigen::Vector3i m_Location;
54 };
55 
56 #endif
Definition: ThreeDGrid.hpp:24
Definition: ThreeDCell.hpp:25
Definition: CollisionSpaceCell.hpp:16
int m_UpdateDirection
Direction from which this voxel was updated.
Definition: CollisionSpaceCell.hpp:40
int m_DistanceSquare
Squared distance from the closest obstacle.
Definition: CollisionSpaceCell.hpp:39
Eigen::Vector3i m_ClosestPoint
Closes obstacle from this voxel.
Definition: CollisionSpaceCell.hpp:41