#include <self_mask_named_link.h>
Definition at line 43 of file self_mask_named_link.h.
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 |
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.
std::string robot_self_filter::SelfMaskNamedLink::tf_prefix_ |
|
protected |
The documentation for this class was generated from the following file: