Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_
00038 #define MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_
00039
00040 #include <boost/utility.hpp>
00041
00042 #include <moveit/collision_detection/collision_matrix.h>
00043 #include <moveit/collision_detection/collision_robot.h>
00044 #include <moveit/collision_detection/world.h>
00045 #include <moveit/macros/class_forward.h>
00046
00048 namespace collision_detection
00049 {
00050 MOVEIT_CLASS_FORWARD(CollisionWorld);
00051
00055 class CollisionWorld : private boost::noncopyable
00056 {
00057 public:
00058 CollisionWorld();
00059
00060 explicit CollisionWorld(const WorldPtr& world);
00061
00064 CollisionWorld(const CollisionWorld& other, const WorldPtr& world);
00065
00066 virtual ~CollisionWorld()
00067 {
00068 }
00069
00070
00071
00072
00073
00079 virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00080 const robot_state::RobotState& state) const;
00081
00088 virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00089 const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
00090
00098 virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00099 const robot_state::RobotState& state1, const robot_state::RobotState& state2) const;
00100
00109 virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00110 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00111 const AllowedCollisionMatrix& acm) const;
00112
00120 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00121 const robot_state::RobotState& state) const = 0;
00122
00130 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00131 const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0;
00132
00141 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00142 const robot_state::RobotState& state1,
00143 const robot_state::RobotState& state2) const = 0;
00144
00154 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00155 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00156 const AllowedCollisionMatrix& acm) const = 0;
00157
00164 virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res,
00165 const CollisionWorld& other_world) const = 0;
00166
00173 virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world,
00174 const AllowedCollisionMatrix& acm) const = 0;
00175
00179 virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state) const = 0;
00180
00186 virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state,
00187 const AllowedCollisionMatrix& acm) const = 0;
00188
00190 virtual double distanceWorld(const CollisionWorld& world) const = 0;
00191
00194 virtual double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm) const = 0;
00198 virtual void setWorld(const WorldPtr& world);
00199
00201 const WorldPtr& getWorld()
00202 {
00203 return world_;
00204 }
00205
00207 const WorldConstPtr& getWorld() const
00208 {
00209 return world_const_;
00210 }
00211
00212 typedef World::ObjectPtr ObjectPtr;
00213 typedef World::ObjectConstPtr ObjectConstPtr;
00214
00215 private:
00216 WorldPtr world_;
00217 WorldConstPtr world_const_;
00218 };
00219 }
00220
00221 #endif