49 ConnectionBasedNodelet::onInit();
52 normals_tree_ = boost::make_shared< pcl::search::KdTree< pcl::PointXYZ > > ();
55 dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_);
56 dynamic_reconfigure::Server<Config>::CallbackType
f =
60 srv_ = pnh_->advertiseService(
63 pub_points_ = advertise< sensor_msgs::PointCloud2 >(*
pnh_,
"output", 1);
64 pub_point_ = advertise< geometry_msgs::PointStamped >(*
pnh_,
"output_point", 1);
65 pub_polygon_ = advertise< geometry_msgs::PolygonStamped >(*
pnh_,
"output_polygon", 1);
161 bool need_resubscribe =
false;
165 need_resubscribe =
true;
188 jsk_recognition_msgs::TransformScreenpoint::Request &
req,
189 jsk_recognition_msgs::TransformScreenpoint::Response &
res)
199 bool need_unsubscribe =
false;
203 need_unsubscribe =
true;
218 if (need_unsubscribe)
234 res.point.x = rx; res.point.y = ry; res.point.z = rz;
242 n3d_.setSearchSurface(
243 boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (
latest_cloud_));
245 pcl::PointCloud<pcl::PointXYZ> cloud_;
250 cloud_.points.resize(0);
251 cloud_.points.push_back(pt);
253 n3d_.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (cloud_));
254 pcl::PointCloud<pcl::Normal> cloud_normals;
255 n3d_.compute (cloud_normals);
257 res.vector.x = cloud_normals.points[0].normal_x;
258 res.vector.y = cloud_normals.points[0].normal_y;
259 res.vector.z = cloud_normals.points[0].normal_z;
261 if((res.point.x * res.vector.x + res.point.y * res.vector.y + res.point.z * res.vector.z) < 0) {
268 geometry_msgs::PointStamped ps;
270 ps.point.x = res.point.x;
271 ps.point.y = res.point.y;
272 ps.point.z = res.point.z;
282 NODELET_DEBUG(
"PointcloudScreenpoint::points_cb, width=%d, height=%d, fields=%ld",
283 msg->width, msg->height, msg->fields.size());
298 geometry_msgs::PointStamped ps;
299 bool ret;
float rx, ry, rz;
303 ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
314 sensor_msgs::PointCloud2 out_pts;
328 pcl::PointCloud<pcl::PointXY>::Ptr point_array_cloud(
new pcl::PointCloud<pcl::PointXY>);
330 pcl::PointCloud<pcl::PointXYZ>::Ptr result_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
332 for (
size_t i = 0; i < point_array_cloud->points.size(); i++) {
333 pcl::PointXY
point = point_array_cloud->points[i];
334 geometry_msgs::PointStamped ps;
335 bool ret;
float rx, ry, rz;
338 pcl::PointXYZ point_on_screen;
339 point_on_screen.x = rx;
340 point_on_screen.y = ry;
341 point_on_screen.z = rz;
342 result_cloud->points.push_back(point_on_screen);
345 sensor_msgs::PointCloud2::Ptr ros_cloud(
new sensor_msgs::PointCloud2);
359 int num_pts = array_ptr->polygon.points.size();
363 }
else if ( num_pts > 2 ) {
365 "Used first 2 points to compute mid-coords.",
366 array_ptr->polygon.points.size());
369 int st_x = array_ptr->polygon.points[0].x;
370 int st_y = array_ptr->polygon.points[0].y;
371 int ed_x = array_ptr->polygon.points[1].x;
372 int ed_y = array_ptr->polygon.points[1].y;
376 geometry_msgs::PointStamped ps;
377 bool ret;
float rx, ry, rz;
381 ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
388 sensor_msgs::PointCloud2 out_pts;
403 geometry_msgs::PolygonStamped result_polygon;
405 for (
size_t i = 0; i < array_ptr->polygon.points.size(); i++) {
406 geometry_msgs::Point32
p = array_ptr->polygon.points[i];
413 geometry_msgs::Point32 p_projected;
417 result_polygon.polygon.points.push_back(p_projected);
424 const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
425 const geometry_msgs::PointStamped::ConstPtr& pt_ptr)
433 const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
434 const sensor_msgs::PointCloud2::ConstPtr& pt_arr_ptr)
442 const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
443 const geometry_msgs::PolygonStamped::ConstPtr& array_ptr)
451 const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
452 const geometry_msgs::PolygonStamped::ConstPtr& array_ptr) {
460 float &resx,
float &resy,
float &resz)
462 if ((x < 0) || (y < 0) || (x >= in_pts.width) || (y >= in_pts.height)) {
464 "point: (%d, %d) size: (%d, %d)",
465 x, y, in_pts.width, in_pts.height);
469 pcl::PointXYZ
p = in_pts.points[in_pts.width * y +
x];
471 NODELET_DEBUG(
"Request: screenpoint (%d, %d) => (%f, %f, %f)", x, y, p.x, p.y, p.z);
474 if ( !std::isnan (p.x) && ((p.x != 0.0) || (p.y != 0.0) || (p.z == 0.0)) ) {
475 resx = p.x; resy = p.y; resz = p.z;
483 float &resx,
float &resy,
float &resz)
487 x = reqx < 0.0 ? ceil(reqx - 0.5) : floor(reqx + 0.5);
488 y = reqy < 0.0 ? ceil(reqy - 0.5) : floor(reqy + 0.5);
491 if (
checkpoint (in_pts, x, y, resx, resy, resz)) {
495 for (
int y2 = 0; y2 <=
n; y2++) {
497 if (
checkpoint (in_pts, x + x2, y + y2, resx, resy, resz)) {
500 if (x2 != 0 && y2 != 0) {
501 if (
checkpoint (in_pts, x - x2, y - y2, resx, resy, resz)) {
506 if (
checkpoint (in_pts, x - x2, y + y2, resx, resy, resz)) {
511 if (
checkpoint (in_pts, x + x2, y - y2, resx, resy, resz)) {
524 sensor_msgs::PointCloud2& out_pts)
526 sensor_msgs::PointCloud2::Ptr points_ptr(
new sensor_msgs::PointCloud2);
529 if ( st_x < 0 ) st_x = 0;
530 if ( st_y < 0 ) st_y = 0;
531 if ( ed_x >= points_ptr->width ) ed_x = points_ptr->width -1;
532 if ( ed_y >= points_ptr->height ) ed_y = points_ptr->height -1;
534 int wd = points_ptr->width;
535 int ht = points_ptr->height;
536 int rstep = points_ptr->row_step;
537 int pstep = points_ptr->point_step;
539 out_pts.header = points_ptr->header;
540 out_pts.width = ed_x - st_x + 1;
541 out_pts.height = ed_y - st_y + 1;
542 out_pts.row_step = out_pts.width * pstep;
543 out_pts.point_step = pstep;
544 out_pts.is_bigendian =
false;
545 out_pts.fields = points_ptr->fields;
546 out_pts.is_dense =
false;
547 out_pts.data.resize(out_pts.row_step * out_pts.height);
549 unsigned char * dst_ptr = &(out_pts.data[0]);
551 for (
size_t idx_y = st_y; idx_y <= ed_y; idx_y++) {
552 for (
size_t idx_x = st_x; idx_x <= ed_x; idx_x++) {
553 const unsigned char * src_ptr = &(points_ptr->data[idx_y * rstep + idx_x * pstep]);
554 memcpy(dst_ptr, src_ptr, pstep);
virtual void unsubscribe()
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_
#define NODELET_ERROR(...)
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_rect_
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_poly_
PointcloudScreenpointConfig Config
void sync_rect_cb(const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
#define NODELET_ERROR_THROTTLE(rate,...)
mf::Subscriber< geometry_msgs::PointStamped > point_sub_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
std_msgs::Header latest_cloud_header_
const ros::Subscriber & getSubscriber() const
boost::shared_ptr< mf::Synchronizer< PointApproxSyncPolicy > > async_point_
bool extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
boost::shared_ptr< mf::Synchronizer< PointExactSyncPolicy > > sync_point_
void point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet)
bool checkpoint(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz)
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_poly_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > dyn_srv_
void sync_point_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
mf::Subscriber< geometry_msgs::PolygonStamped > rect_sub_
void point_cb(const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
void sync_point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
virtual void configCallback(Config &config, uint32_t level)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
ros::Publisher pub_point_
bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res)
#define NODELET_INFO_THROTTLE(rate,...)
mf::Subscriber< sensor_msgs::PointCloud2 > points_sub_
ros::Publisher pub_points_
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)
mf::Subscriber< geometry_msgs::PolygonStamped > poly_sub_
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
void poly_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_rect_
pcl::PointCloud< pcl::PointXYZ > latest_cloud_
void rect_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
void sync_poly_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PointCloudApproxSyncPolicy > > async_point_array_
ros::Publisher pub_polygon_
ROSCPP_DECL void spinOnce()
#define NODELET_DEBUG(...)
boost::shared_ptr< mf::Synchronizer< PointCloudExactSyncPolicy > > sync_point_array_
mf::Subscriber< sensor_msgs::PointCloud2 > point_array_sub_
Connection registerCallback(const C &callback)