MoveItCollisionMatrixManipulator.h
Go to the documentation of this file.
00001 #ifndef OBJECT_MOVEIT_MOVEITCOLLISIONMATRIXMANIPULATOR
00002 #define OBJECT_MOVEIT_MOVEITCOLLISIONMATRIXMANIPULATOR
00003 
00004 /*#include <capabilities/MoveItHelpers.h>
00005 #include <phd_experiments/general_helpers.h>
00006 */
00007 #include <moveit_msgs/GetPlanningScene.h>
00008 #include <moveit_msgs/AllowedCollisionMatrix.h>
00009 #include <moveit_msgs/CollisionObject.h>
00010 
00011 /*#include <moveit_msgs/AllowedCollisionEntry.h>
00012 #include <moveit_msgs/GetCartesianPath.h>
00013 */
00014 
00015 #include <ros/ros.h>
00016 
00017 namespace moveit_object_handling
00018 {
00019 
00033 class MoveItCollisionMatrixManipulator
00034 {
00035 public:
00036     MoveItCollisionMatrixManipulator(ros::NodeHandle& nh);
00037     ~MoveItCollisionMatrixManipulator();
00038 
00042     bool getCurrentMoveItAllowedCollisionMatrix(moveit_msgs::AllowedCollisionMatrix& matrix);
00043 
00047     bool setAllowedMoveItCollisionMatrix(moveit_msgs::AllowedCollisionMatrix& m);
00048 
00053     bool addAllowedMoveItCollision(const std::string& name, const std::vector<std::string>& linkNames);
00054 
00062     bool setAllowedMoveItCollision(const std::string& name1, const std::string& name2, const bool flag);
00063 
00071     bool attachMoveItObjectToRobot(const std::string& name, const std::string& link_name,
00072                                    const std::vector<std::string>& allowedTouchLinks);
00073 
00079     bool detachMoveItObjectFromRobot(const std::string& name);
00080 
00081 private:
00082 
00086     void expandMoveItCollisionMatrix(const std::string& name, moveit_msgs::AllowedCollisionMatrix& m, bool default_val);
00087 
00088 
00089     bool getMoveItScene(octomap_msgs::OctomapWithPose & octomap,
00090                         std::vector<moveit_msgs::CollisionObject>& collision_objects);
00091 
00092     bool hasObject(const std::string& name, const std::vector<moveit_msgs::AttachedCollisionObject>& objs,
00093                    moveit_msgs::AttachedCollisionObject& o);
00094 
00095     bool hasObject(const std::string& name, const std::vector<moveit_msgs::CollisionObject>& objs,
00096                    moveit_msgs::CollisionObject& o);
00097 
00098     bool removeObject(const std::string& name, std::vector<moveit_msgs::CollisionObject>& objs);
00099 
00100     bool removeObject(const std::string& name, std::vector<moveit_msgs::AttachedCollisionObject>& objs);
00101 
00106     std::vector<std::string>::iterator ensureExistsInACM(
00107         const std::string& name, moveit_msgs::AllowedCollisionMatrix& m, bool initFlag);
00108 
00109 
00110     std::string SET_PLANNING_SCENE_TOPIC;
00111     std::string GET_PLANNING_SCENE_TOPIC;
00112 
00113     ros::Publisher planning_scene_publisher;
00114     ros::ServiceClient planning_scene_client;
00115 };  // class
00116 
00117 }  // namespace
00118 #endif


moveit_object_handling
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:50:51