37 #ifndef JSK_PCL_ROS_COLLISION_DETECTOR_H_ 38 #define JSK_PCL_ROS_COLLISION_DETECTOR_H_ 41 #include <sensor_msgs/PointCloud2.h> 42 #include <jsk_recognition_msgs/CheckCollision.h> 44 #include <pcl/point_types.h> 48 #include <std_msgs/Bool.h> 67 const geometry_msgs::PoseStamped&
pose);
70 jsk_recognition_msgs::CheckCollision::Response &
res);
79 pcl::PointCloud<pcl::PointXYZ>
cloud_;
std::string world_frame_id_
ros::ServiceServer service_
pcl::PointCloud< pcl::PointXYZ > cloud_
tf::TransformBroadcaster tf_broadcaster_
tf::TransformListener tf_listener_
virtual void unsubscribe()
virtual void initSelfMask()
boost::shared_ptr< robot_self_filter::SelfMaskUrdfRobot > self_mask_
boost::mutex mutex
global mutex.
std::string cloud_frame_id_
virtual bool checkCollision(const sensor_msgs::JointState &joint, const geometry_msgs::PoseStamped &pose)
virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< CollisionDetector > Ptr
virtual bool serviceCallback(jsk_recognition_msgs::CheckCollision::Request &req, jsk_recognition_msgs::CheckCollision::Response &res)