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