Go to the documentation of this file.
36 #ifndef JSK_PCL_ROS_UTILS_POLYGON_TRANSFORMER_H_
37 #define JSK_PCL_ROS_UTILS_POLYGON_TRANSFORMER_H_
41 #include <sensor_msgs/PointCloud2.h>
45 #include <jsk_recognition_msgs/PolygonArray.h>
46 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
55 #include <jsk_topic_tools/connection_based_nodelet.h>
59 class PolygonArrayTransformer:
public jsk_topic_tools::ConnectionBasedNodelet
63 jsk_recognition_msgs::PolygonArray,
64 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
68 virtual void transform(
const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
69 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients);
76 const geometry_msgs::PolygonStamped& polygon,
77 geometry_msgs::PolygonStamped& result);
pcl::ModelCoefficients PCLModelCoefficientMsg
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43