#include <polygon_array_transformer.h>
Definition at line 91 of file polygon_array_transformer.h.
◆ SyncPolicy
◆ ~PolygonArrayTransformer()
jsk_pcl_ros_utils::PolygonArrayTransformer::~PolygonArrayTransformer |
( |
| ) |
|
|
virtual |
◆ computeCoefficients()
void jsk_pcl_ros_utils::PolygonArrayTransformer::computeCoefficients |
( |
const geometry_msgs::PolygonStamped & |
polygon, |
|
|
PCLModelCoefficientMsg & |
coefficient |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros_utils::PolygonArrayTransformer::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros_utils::PolygonArrayTransformer::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ transform()
void jsk_pcl_ros_utils::PolygonArrayTransformer::transform |
( |
const jsk_recognition_msgs::PolygonArray::ConstPtr & |
polygons, |
|
|
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr & |
coefficients |
|
) |
| |
|
protectedvirtual |
◆ transformModelCoefficient()
◆ transformPolygon()
void jsk_pcl_ros_utils::PolygonArrayTransformer::transformPolygon |
( |
const Eigen::Affine3d & |
transform, |
|
|
const geometry_msgs::PolygonStamped & |
polygon, |
|
|
geometry_msgs::PolygonStamped & |
result |
|
) |
| |
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros_utils::PolygonArrayTransformer::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ coefficients_pub_
ros::Publisher jsk_pcl_ros_utils::PolygonArrayTransformer::coefficients_pub_ |
|
protected |
◆ frame_id_
std::string jsk_pcl_ros_utils::PolygonArrayTransformer::frame_id_ |
|
protected |
◆ listener_
◆ polygons_pub_
ros::Publisher jsk_pcl_ros_utils::PolygonArrayTransformer::polygons_pub_ |
|
protected |
◆ sub_coefficients_
message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros_utils::PolygonArrayTransformer::sub_coefficients_ |
|
protected |
◆ sub_polygons_
◆ sync_
The documentation for this class was generated from the following files: