Public Member Functions | Protected Attributes | List of all members
robot_self_filter::SelfMaskNamedLink Class Reference

#include <self_mask_named_link.h>

Inheritance diagram for robot_self_filter::SelfMaskNamedLink:
Inheritance graph
[legend]

Public Member Functions

bool assumeFrame (const std_msgs::Header &header)
 Assume subsequent calls to getMaskX() will be in the frame passed to this function. This is override function to use tf_prefix. The frame in which the sensor is located is optional. More...
 
int getMaskContainmentforNamedLink (const tf::Vector3 &pt, const std::string name) const
 
int getMaskContainmentforNamedLink (double x, double y, double z, const std::string name) const
 Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use. More...
 
 SelfMaskNamedLink (tf::TransformListener &tf, const std::vector< LinkInfo > &links, const std::string &tf_prefix="")
 Construct the filter. More...
 

Protected Attributes

std::string tf_prefix_
 

Detailed Description

Definition at line 43 of file self_mask_named_link.h.

Constructor & Destructor Documentation

robot_self_filter::SelfMaskNamedLink::SelfMaskNamedLink ( tf::TransformListener tf,
const std::vector< LinkInfo > &  links,
const std::string tf_prefix = "" 
)
inline

Construct the filter.

Definition at line 50 of file self_mask_named_link.h.

Member Function Documentation

bool robot_self_filter::SelfMaskNamedLink::assumeFrame ( const std_msgs::Header header)
inline

Assume subsequent calls to getMaskX() will be in the frame passed to this function. This is override function to use tf_prefix. The frame in which the sensor is located is optional.

Definition at line 62 of file self_mask_named_link.h.

int robot_self_filter::SelfMaskNamedLink::getMaskContainmentforNamedLink ( const tf::Vector3 pt,
const std::string  name 
) const
inline

Definition at line 91 of file self_mask_named_link.h.

int robot_self_filter::SelfMaskNamedLink::getMaskContainmentforNamedLink ( double  x,
double  y,
double  z,
const std::string  name 
) const
inline

Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use.

Definition at line 109 of file self_mask_named_link.h.

Member Data Documentation

std::string robot_self_filter::SelfMaskNamedLink::tf_prefix_
protected

Definition at line 114 of file self_mask_named_link.h.


The documentation for this class was generated from the following file:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:48