#include <hinted_stick_finder.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | ASyncPolicy |
typedef HintedStickFinderConfig | Config |
Public Types inherited from jsk_topic_tools::DiagnosticNodelet | |
typedef boost::shared_ptr< DiagnosticNodelet > | Ptr |
Public Member Functions | |
HintedStickFinder () | |
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 | cloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) |
Non synchronized message callback for ~input pointcloud. More... | |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | detect (const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) |
Synchronized message callback. More... | |
virtual void | filterPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const jsk_recognition_utils::ConvexPolygon::Ptr polygon, pcl::PointIndices &output_indices) |
virtual void | fittingCylinder (const pcl::PointCloud< pcl::PointXYZ >::Ptr &filtered_cloud, const pcl::PointCloud< pcl::Normal >::Ptr &cloud_nromals, const Eigen::Vector3f &a, const Eigen::Vector3f &b) |
virtual void | hintCallback (const geometry_msgs::PolygonStamped::ConstPtr &hint_msg) |
Non synchronized message callback for ~input/hint/line. More... | |
virtual void | infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg) |
Non synchronized message callback for ~input/camera_info. More... | |
virtual void | normalEstimate (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::PointIndices::Ptr indices, pcl::PointCloud< pcl::Normal > &normals, pcl::PointCloud< pcl::PointXYZ > &normals_cloud) |
virtual void | onInit () |
virtual jsk_recognition_utils::ConvexPolygon::Ptr | polygonFromLine (const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const image_geometry::PinholeCameraModel &model, Eigen::Vector3f &a, Eigen::Vector3f &b) |
virtual bool | rejected2DHint (const jsk_recognition_utils::Cylinder::Ptr &cylinder, const Eigen::Vector3f &a, const Eigen::Vector3f &b) |
Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_, return false. More... | |
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 59 of file hinted_stick_finder.h.
typedef message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> jsk_pcl_ros::HintedStickFinder::ASyncPolicy |
Definition at line 65 of file hinted_stick_finder.h.
typedef HintedStickFinderConfig jsk_pcl_ros::HintedStickFinder::Config |
Definition at line 66 of file hinted_stick_finder.h.
|
inline |
Definition at line 67 of file hinted_stick_finder.h.
|
protectedvirtual |
Non synchronized message callback for ~input pointcloud.
Definition at line 96 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 353 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Synchronized message callback.
Definition at line 140 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 304 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 223 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Non synchronized message callback for ~input/hint/line.
Definition at line 111 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Non synchronized message callback for ~input/camera_info.
Definition at line 118 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 187 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 49 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 327 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_, return false.
cylinder | Cylinder object |
a | 3-D ray to start point of 2-D line |
b | 3-D ray to end point of 2-D line |
Definition at line 207 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 74 of file hinted_stick_finder_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 126 of file hinted_stick_finder_nodelet.cpp.
|
protected |
Definition at line 163 of file hinted_stick_finder.h.
|
protected |
Definition at line 165 of file hinted_stick_finder.h.
|
protected |
Definition at line 161 of file hinted_stick_finder.h.
|
protected |
Definition at line 158 of file hinted_stick_finder.h.
|
protected |
Definition at line 178 of file hinted_stick_finder.h.
|
protected |
Definition at line 179 of file hinted_stick_finder.h.
|
protected |
Definition at line 160 of file hinted_stick_finder.h.
|
protected |
Definition at line 156 of file hinted_stick_finder.h.
|
protected |
Definition at line 164 of file hinted_stick_finder.h.
|
protected |
Definition at line 162 of file hinted_stick_finder.h.
|
protected |
Definition at line 157 of file hinted_stick_finder.h.
|
protected |
Definition at line 136 of file hinted_stick_finder.h.
|
protected |
Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messages but keep processing with old hint information.
Definition at line 176 of file hinted_stick_finder.h.
|
protected |
Definition at line 159 of file hinted_stick_finder.h.
|
protected |
Definition at line 149 of file hinted_stick_finder.h.
|
protected |
Definition at line 146 of file hinted_stick_finder.h.
|
protected |
Definition at line 147 of file hinted_stick_finder.h.
|
protected |
Definition at line 148 of file hinted_stick_finder.h.
|
protected |
Definition at line 144 of file hinted_stick_finder.h.
|
protected |
Definition at line 145 of file hinted_stick_finder.h.
|
protected |
Definition at line 154 of file hinted_stick_finder.h.
|
protected |
Definition at line 140 of file hinted_stick_finder.h.
|
protected |
Definition at line 139 of file hinted_stick_finder.h.
|
protected |
Definition at line 152 of file hinted_stick_finder.h.
|
protected |
Definition at line 151 of file hinted_stick_finder.h.
|
protected |
Definition at line 153 of file hinted_stick_finder.h.
|
protected |
Definition at line 141 of file hinted_stick_finder.h.
|
protected |
Definition at line 138 of file hinted_stick_finder.h.
|
protected |
Definition at line 142 of file hinted_stick_finder.h.
|
protected |
True if use ~input has normal fields.
Definition at line 170 of file hinted_stick_finder.h.