Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_SELF_MASK_NAMED_LINK_H_ 
   37 #define JSK_PCL_ROS_SELF_MASK_NAMED_LINK_H_ 
   43   class SelfMaskNamedLink : 
public SelfMask<pcl::PointXYZ>
 
   63        const unsigned int bs = 
bodies_.size();
 
   66        for (
unsigned int i = 0 ; 
i < bs ; ++
i) {
 
   69            ROS_ERROR(
"WaitForTransform timed out from %s to %s after 100ms.  Error string: %s", (
tf_prefix_+
bodies_[i].name).c_str(), 
header.frame_id.c_str(), err.c_str());
 
   92        const unsigned int bs = 
bodies_.size();
 
   94        for (
unsigned int j = 0 ; out == 
OUTSIDE && j < bs ; ++j) {
 
   96            if (
bodies_[j].body->containsPoint(pt))
 
  
void computeBoundingSpheres(void)
bool assumeFrame(const std_msgs::Header &header)
Assume subsequent calls to getMaskX() will be in the frame passed to this function....
int getMaskContainmentforNamedLink(const tf::Vector3 &pt, const std::string name) const
std::vector< SeeLink > bodies_
SelfMaskNamedLink(tf::TransformListener &tf, const std::vector< LinkInfo > &links, const std::string &tf_prefix="")
Construct the filter.
SelfMask(tf::TransformListener &tf, const std::vector< LinkInfo > &links)
tf::TransformListener & tf_
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:12