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
00036 #include "jsk_pcl_ros/pcl_conversion_util.h"
00037 #include "jsk_pcl_ros/plane_reasoner.h"
00038 #include <tf_conversions/tf_eigen.h>
00039
00040 namespace jsk_pcl_ros
00041 {
00042 void PlaneReasoner::onInit()
00043 {
00045
00047 DiagnosticNodelet::onInit();
00048 tf_listener_ = TfListenerSingleton::getInstance();
00049
00051
00053 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00054 dynamic_reconfigure::Server<Config>::CallbackType f =
00055 boost::bind (
00056 &PlaneReasoner::configCallback, this, _1, _2);
00057 srv_->setCallback (f);
00058
00060
00062 pub_vertical_inliers_
00063 = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/vertical/inliers", 1);
00064 pub_vertical_coefficients_
00065 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/vertical/coefficients", 1);
00066 pub_vertical_polygons_
00067 = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/vertical/polygons", 1);
00068 pub_horizontal_inliers_
00069 = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/horizontal/inliers", 1);
00070 pub_horizontal_coefficients_
00071 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/horizontal/coefficients", 1);
00072 pub_horizontal_polygons_
00073 = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/horizontal/polygons", 1);
00074 }
00075
00076 void PlaneReasoner::subscribe()
00077 {
00079
00081 sub_input_.subscribe(*pnh_, "input", 1);
00082 sub_inliers_.subscribe(*pnh_, "input_inliers", 1);
00083 sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00084 sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00085 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00086 sync_->connectInput(sub_input_, sub_inliers_,
00087 sub_coefficients_, sub_polygons_);
00088 sync_->registerCallback(boost::bind(&PlaneReasoner::reason,
00089 this, _1, _2, _3, _4));
00090 }
00091
00092 void PlaneReasoner::unsubscribe()
00093 {
00094 sub_input_.unsubscribe();
00095 sub_inliers_.unsubscribe();
00096 sub_coefficients_.unsubscribe();
00097 sub_polygons_.unsubscribe();
00098 }
00099
00100
00101 void PlaneReasoner::configCallback(Config &config, uint32_t level)
00102 {
00103 boost::mutex::scoped_lock lock(mutex_);
00104 global_frame_id_ = config.global_frame_id;
00105 horizontal_angular_threshold_ = config.horizontal_angular_threshold;
00106 vertical_angular_threshold_ = config.vertical_angular_threshold;
00107 }
00108
00109 void PlaneReasoner::updateDiagnostic(
00110 diagnostic_updater::DiagnosticStatusWrapper &stat)
00111 {
00112 if (vital_checker_->isAlive()) {
00113 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00114 name_ + " running");
00115 }
00116 else {
00117 jsk_topic_tools::addDiagnosticErrorSummary(
00118 name_, vital_checker_, stat);
00119 }
00120 }
00121
00122 void PlaneReasoner::reason(
00123 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00124 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
00125 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00126 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg)
00127 {
00128 boost::mutex::scoped_lock lock(mutex_);
00129
00130 if ((inliers_msg->cluster_indices.size()
00131 != coefficients_msg->coefficients.size()) ||
00132 (inliers_msg->cluster_indices.size()
00133 != polygons_msg->polygons.size())) {
00134 JSK_NODELET_FATAL("the size of inliers, coefficients and polygons are not same");
00135 return;
00136 }
00137 vital_checker_->poke();
00138 pcl::PointCloud<PointT>::Ptr input_cloud (new pcl::PointCloud<PointT>);
00139 pcl::fromROSMsg(*cloud_msg, *input_cloud);
00140
00141
00142 std::vector<pcl::PointIndices::Ptr> inliers
00143 = pcl_conversions::convertToPCLPointIndices(inliers_msg->cluster_indices);
00144 std::vector<pcl::ModelCoefficients::Ptr> coefficients
00145 = pcl_conversions::convertToPCLModelCoefficients(
00146 coefficients_msg->coefficients);
00147 std::vector<Plane::Ptr> planes = convertToPlanes(coefficients);
00148 std::vector<geometry_msgs::PolygonStamped> polygons = polygons_msg->polygons;
00149 std::vector<PlaneInfoContainer> plane_infos
00150 = packInfo(inliers, coefficients, planes, polygons);
00151 std::vector<PlaneInfoContainer> horizontal_planes
00152 = filterHorizontalPlanes(plane_infos);
00153 std::vector<PlaneInfoContainer> vertical_planes
00154 = filterVerticalPlanes(plane_infos);
00155 publishPlaneInfo(vertical_planes,
00156 cloud_msg->header,
00157 input_cloud,
00158 pub_vertical_inliers_,
00159 pub_vertical_coefficients_,
00160 pub_vertical_polygons_);
00161 publishPlaneInfo(horizontal_planes,
00162 cloud_msg->header,
00163 input_cloud,
00164 pub_horizontal_inliers_,
00165 pub_horizontal_coefficients_,
00166 pub_horizontal_polygons_);
00167 }
00168
00169 void PlaneReasoner::publishPlaneInfo(
00170 std::vector<PlaneInfoContainer>& containers,
00171 const std_msgs::Header& header,
00172 pcl::PointCloud<PointT>::Ptr cloud,
00173 ros::Publisher& pub_inlier,
00174 ros::Publisher& pub_coefficients,
00175 ros::Publisher& pub_polygons)
00176 {
00177 std::vector<pcl::PointIndices::Ptr> inliers;
00178 std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00179 std::vector<geometry_msgs::PolygonStamped> polygons;
00180 for (size_t i = 0; i < containers.size(); i++) {
00181 inliers.push_back(containers[i].get<0>());
00182 coefficients.push_back(containers[i].get<1>());
00183 polygons.push_back(containers[i].get<3>());
00184 }
00185 jsk_recognition_msgs::ClusterPointIndices ros_indices;
00186 jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00187 jsk_recognition_msgs::PolygonArray ros_polygons;
00188 ros_indices.header = header;
00189 ros_coefficients.header = header;
00190 ros_polygons.header = header;
00191 ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
00192 inliers, header);
00193 ros_coefficients.coefficients
00194 = pcl_conversions::convertToROSModelCoefficients(
00195 coefficients, header);
00196 ros_polygons.polygons = polygons;
00197 pub_inlier.publish(ros_indices);
00198 pub_coefficients.publish(ros_coefficients);
00199 pub_polygons.publish(ros_polygons);
00200 }
00201
00202 std::vector<PlaneInfoContainer>
00203 PlaneReasoner::filterPlanesAroundAngle(
00204 double reference_angle,
00205 double thrshold,
00206 std::vector<PlaneInfoContainer>& infos)
00207 {
00208
00209 std::vector<PlaneInfoContainer> ret;
00210 for (size_t i = 0; i < infos.size(); i++) {
00211 PlaneInfoContainer plane_info = infos[i];
00212 if (tf_listener_->canTransform(global_frame_id_,
00213 plane_info.get<3>().header.frame_id,
00214 plane_info.get<3>().header.stamp)) {
00215 tf::StampedTransform transform;
00216 tf_listener_->lookupTransform(plane_info.get<3>().header.frame_id, global_frame_id_,
00217
00218 plane_info.get<3>().header.stamp,
00219 transform);
00220 Eigen::Affine3d eigen_transform;
00221 tf::transformTFToEigen(transform, eigen_transform);
00222 Eigen::Affine3f eigen_transform_3f;
00223 Eigen::Vector3d up_d = (eigen_transform.rotation() * Eigen::Vector3d(0, 0, 1));
00224 Eigen::Vector3f up;
00225 pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(up_d, up);
00226 Plane::Ptr plane = plane_info.get<2>();
00227 double angle = plane->angle(up);
00228
00229
00230
00231 if (fabs(angle - reference_angle) < thrshold) {
00232 ret.push_back(plane_info);
00233 }
00234 }
00235 }
00236 return ret;
00237 }
00238
00239 std::vector<PlaneInfoContainer>
00240 PlaneReasoner::filterHorizontalPlanes(
00241 std::vector<PlaneInfoContainer>& infos)
00242 {
00243 return filterPlanesAroundAngle(
00244 0,
00245 horizontal_angular_threshold_,
00246 infos);
00247 }
00248
00249 std::vector<PlaneInfoContainer>
00250 PlaneReasoner::filterVerticalPlanes(
00251 std::vector<PlaneInfoContainer>& infos)
00252 {
00253 return filterPlanesAroundAngle(
00254 M_PI / 2.0,
00255 vertical_angular_threshold_,
00256 infos);
00257 }
00258
00259 std::vector<PlaneInfoContainer>
00260 PlaneReasoner::packInfo(
00261 std::vector<pcl::PointIndices::Ptr>& inliers,
00262 std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00263 std::vector<Plane::Ptr>& planes,
00264 std::vector<geometry_msgs::PolygonStamped>& polygons)
00265 {
00266 std::vector<PlaneInfoContainer> ret;
00267 for (size_t i = 0; i < inliers.size(); i++) {
00268 ret.push_back(boost::make_tuple<pcl::PointIndices::Ptr,
00269 pcl::ModelCoefficients::Ptr,
00270 Plane::Ptr>(inliers[i], coefficients[i],
00271 planes[i], polygons[i]));
00272 }
00273 return ret;
00274 }
00275
00276
00277 }
00278
00279 #include <pluginlib/class_list_macros.h>
00280 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PlaneReasoner, nodelet::Nodelet);