Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/centroid_publisher.h"
00037
00038 #include <geometry_msgs/PoseStamped.h>
00039 #include <geometry_msgs/PointStamped.h>
00040
00041 #include <pcl/common/centroid.h>
00042 #include "jsk_pcl_ros/pcl_conversion_util.h"
00043
00044 namespace jsk_pcl_ros
00045 {
00046 void CentroidPublisher::extract(const sensor_msgs::PointCloud2ConstPtr& input)
00047 {
00048 pcl::PointCloud<pcl::PointXYZ> cloud_xyz;
00049 pcl::fromROSMsg(*input, cloud_xyz);
00050 Eigen::Vector4f center;
00051 pcl::compute3DCentroid(cloud_xyz, center);
00052 if (publish_tf_) {
00053 tf::Transform transform;
00054 transform.setOrigin(tf::Vector3(center[0], center[1], center[2]));
00055 transform.setRotation(tf::createIdentityQuaternion());
00056 br_.sendTransform(tf::StampedTransform(transform, input->header.stamp,
00057 input->header.frame_id, frame_));
00058 }
00059 geometry_msgs::PoseStamped pose;
00060 pose.pose.orientation.w = 1.0;
00061 pose.pose.position.x = center[0];
00062 pose.pose.position.y = center[1];
00063 pose.pose.position.z = center[2];
00064 pose.header = input->header;
00065 pub_pose_.publish(pose);
00066 geometry_msgs::PointStamped point;
00067 point.point.x = center[0];
00068 point.point.y = center[1];
00069 point.point.z = center[2];
00070 point.header = input->header;
00071 pub_point_.publish(point);
00072 }
00073
00074 void CentroidPublisher::subscribe()
00075 {
00076 sub_input_ = pnh_->subscribe("input", 1, &CentroidPublisher::extract, this);
00077 }
00078
00079 void CentroidPublisher::unsubscribe()
00080 {
00081 sub_input_.shutdown();
00082 }
00083
00084 void CentroidPublisher::onInit(void)
00085 {
00086 DiagnosticNodelet::onInit();
00087 pnh_->param("publish_tf", publish_tf_, false);
00088 if (publish_tf_) {
00089 if (!pnh_->getParam("frame", frame_))
00090 {
00091 JSK_ROS_WARN("~frame is not specified, using %s", getName().c_str());
00092 frame_ = getName();
00093 }
00094
00095 pub_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>("output/pose", 1);
00096 pub_point_ = pnh_->advertise<geometry_msgs::PointStamped>(
00097 "output/point", 1);
00098 subscribe();
00099 }
00100 else {
00101 pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose", 1);
00102 pub_point_ = advertise<geometry_msgs::PointStamped>(
00103 *pnh_, "output/point", 1);
00104 }
00105 }
00106 }
00107
00108 #include <pluginlib/class_list_macros.h>
00109 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::CentroidPublisher, nodelet::Nodelet);