#include <plane_reasoner.h>
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual std::vector< PlaneInfoContainer > | filterHorizontalPlanes (std::vector< PlaneInfoContainer > &infos) |
|
virtual std::vector< PlaneInfoContainer > | filterPlanesAroundAngle (double reference_angle, double thrshold, std::vector< PlaneInfoContainer > &infos) |
|
virtual std::vector< PlaneInfoContainer > | filterVerticalPlanes (std::vector< PlaneInfoContainer > &infos) |
|
virtual void | onInit () |
|
virtual std::vector< PlaneInfoContainer > | packInfo (std::vector< pcl::PointIndices::Ptr > &inliers, std::vector< pcl::ModelCoefficients::Ptr > &coefficients, std::vector< jsk_recognition_utils::Plane::Ptr > &planes, std::vector< geometry_msgs::PolygonStamped > &polygons) |
|
virtual void | publishPlaneInfo (std::vector< PlaneInfoContainer > &containers, const std_msgs::Header &header, pcl::PointCloud< PointT >::Ptr cloud, ros::Publisher &pub_inlier, ros::Publisher &pub_coefficients, ros::Publisher &pub_polygons) |
|
virtual void | reason (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &inliers_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons_msg) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
Definition at line 95 of file plane_reasoner.h.
◆ Config
◆ PointT
◆ SyncPolicy
◆ PlaneReasoner()
jsk_pcl_ros_utils::PlaneReasoner::PlaneReasoner |
( |
| ) |
|
|
inline |
◆ ~PlaneReasoner()
jsk_pcl_ros_utils::PlaneReasoner::~PlaneReasoner |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_pcl_ros_utils::PlaneReasoner::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ filterHorizontalPlanes()
◆ filterPlanesAroundAngle()
◆ filterVerticalPlanes()
◆ onInit()
void jsk_pcl_ros_utils::PlaneReasoner::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ packInfo()
◆ publishPlaneInfo()
◆ reason()
void jsk_pcl_ros_utils::PlaneReasoner::reason |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & |
inliers_msg, |
|
|
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr & |
coefficients_msg, |
|
|
const jsk_recognition_msgs::PolygonArray::ConstPtr & |
polygons_msg |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros_utils::PlaneReasoner::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros_utils::PlaneReasoner::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ global_frame_id_
std::string jsk_pcl_ros_utils::PlaneReasoner::global_frame_id_ |
|
protected |
◆ horizontal_angular_threshold_
double jsk_pcl_ros_utils::PlaneReasoner::horizontal_angular_threshold_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros_utils::PlaneReasoner::mutex_ |
|
protected |
◆ pub_horizontal_coefficients_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_horizontal_coefficients_ |
|
protected |
◆ pub_horizontal_inliers_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_horizontal_inliers_ |
|
protected |
◆ pub_horizontal_polygons_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_horizontal_polygons_ |
|
protected |
◆ pub_vertical_coefficients_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_vertical_coefficients_ |
|
protected |
◆ pub_vertical_inliers_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_vertical_inliers_ |
|
protected |
◆ pub_vertical_polygons_
ros::Publisher jsk_pcl_ros_utils::PlaneReasoner::pub_vertical_polygons_ |
|
protected |
◆ srv_
◆ sub_coefficients_
◆ sub_inliers_
◆ sub_input_
◆ sub_polygons_
◆ sync_
◆ tf_listener_
◆ vertical_angular_threshold_
double jsk_pcl_ros_utils::PlaneReasoner::vertical_angular_threshold_ |
|
protected |
The documentation for this class was generated from the following files: