#include <pointcloud_screenpoint.h>
Protected Types | |
typedef PointcloudScreenpointConfig | Config |
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | PointApproxSyncPolicy |
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | PointCloudApproxSyncPolicy |
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | PointCloudExactSyncPolicy |
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | PointExactSyncPolicy |
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > | PolygonApproxSyncPolicy |
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > | PolygonExactSyncPolicy |
Protected Member Functions | |
bool | checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz) |
virtual void | configCallback (Config &config, uint32_t level) |
bool | extract_point (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz) |
void | extract_rect (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int st_x, int st_y, int ed_x, int ed_y, sensor_msgs::PointCloud2 &out_pts) |
virtual void | onInit () |
void | point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr) |
void | point_cb (const geometry_msgs::PointStamped::ConstPtr &pt_ptr) |
void | points_cb (const sensor_msgs::PointCloud2::ConstPtr &msg) |
void | poly_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
void | rect_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
bool | screenpoint_cb (jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res) |
virtual void | subscribe () |
void | sync_point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr) |
void | sync_point_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr) |
void | sync_poly_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
void | sync_rect_cb (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
virtual void | unsubscribe () |
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 |
Additional Inherited Members | |
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 () |
Definition at line 56 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 59 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 68 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 72 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 85 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 81 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 64 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 77 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 458 of file pointcloud_screenpoint_nodelet.cpp.
|
protectedvirtual |
Definition at line 157 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 481 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 521 of file pointcloud_screenpoint_nodelet.cpp.
|
protectedvirtual |
Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 47 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 320 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 289 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 280 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 394 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 352 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 187 of file pointcloud_screenpoint_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 70 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 432 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 423 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 441 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 450 of file pointcloud_screenpoint_nodelet.cpp.
|
protectedvirtual |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 148 of file pointcloud_screenpoint_nodelet.cpp.
|
protected |
Definition at line 152 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 138 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 139 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 140 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 137 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 155 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 127 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 159 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 158 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 126 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 148 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 149 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 135 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 134 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 132 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 136 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 129 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 128 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 130 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 153 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 133 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 154 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 131 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 143 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 144 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 145 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 142 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 152 of file pointcloud_screenpoint.h.
|
protected |
Definition at line 156 of file pointcloud_screenpoint.h.