#include <plane_reasoner.h>
Public Types | |
typedef jsk_pcl_ros_utils::PlaneReasonerConfig | Config |
typedef pcl::PointXYZRGB | PointT |
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray > | SyncPolicy |
Public Types inherited from jsk_topic_tools::DiagnosticNodelet | |
typedef boost::shared_ptr< DiagnosticNodelet > | Ptr |
Public Member Functions | |
PlaneReasoner () | |
Public Member Functions inherited from jsk_topic_tools::DiagnosticNodelet | |
DiagnosticNodelet (const std::string &name) | |
Public Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet | |
ConnectionBasedNodelet () | |
Public Member Functions inherited from nodelet::Nodelet | |
void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
Nodelet () | |
virtual | ~Nodelet () |
Protected Member Functions | |
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 () |
Protected Member Functions inherited from jsk_topic_tools::DiagnosticNodelet | |
virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Protected Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet | |
ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size) |
image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
virtual void | cameraConnectionBaseCallback () |
virtual void | cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
virtual void | cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub) |
virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
virtual void | imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
virtual bool | isSubscribed () |
virtual void | onInitPostProcess () |
virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) |
virtual void | warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event) |
Protected Member Functions inherited from nodelet::Nodelet | |
ros::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
Definition at line 63 of file plane_reasoner.h.
typedef jsk_pcl_ros_utils::PlaneReasonerConfig jsk_pcl_ros_utils::PlaneReasoner::Config |
Definition at line 74 of file plane_reasoner.h.
typedef pcl::PointXYZRGB jsk_pcl_ros_utils::PlaneReasoner::PointT |
Definition at line 75 of file plane_reasoner.h.
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray> jsk_pcl_ros_utils::PlaneReasoner::SyncPolicy |
Definition at line 73 of file plane_reasoner.h.
|
inline |
Definition at line 78 of file plane_reasoner.h.
|
protectedvirtual |
Definition at line 103 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 229 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 192 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 239 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 42 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 249 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 158 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Definition at line 111 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 78 of file plane_reasoner_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 94 of file plane_reasoner_nodelet.cpp.
|
protected |
Definition at line 148 of file plane_reasoner.h.
|
protected |
Definition at line 149 of file plane_reasoner.h.
|
protected |
Definition at line 143 of file plane_reasoner.h.
|
protected |
Definition at line 140 of file plane_reasoner.h.
|
protected |
Definition at line 139 of file plane_reasoner.h.
|
protected |
Definition at line 141 of file plane_reasoner.h.
|
protected |
Definition at line 137 of file plane_reasoner.h.
|
protected |
Definition at line 136 of file plane_reasoner.h.
|
protected |
Definition at line 138 of file plane_reasoner.h.
|
protected |
Definition at line 134 of file plane_reasoner.h.
|
protected |
Definition at line 131 of file plane_reasoner.h.
|
protected |
Definition at line 130 of file plane_reasoner.h.
|
protected |
Definition at line 129 of file plane_reasoner.h.
|
protected |
Definition at line 132 of file plane_reasoner.h.
|
protected |
Definition at line 133 of file plane_reasoner.h.
|
protected |
Definition at line 135 of file plane_reasoner.h.
|
protected |
Definition at line 150 of file plane_reasoner.h.