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/plane_rejector.h"
00037 #include <pluginlib/class_list_macros.h>
00038
00039 #include <geometry_msgs/Vector3Stamped.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041
00042 namespace jsk_pcl_ros
00043 {
00044 void PlaneRejector::onInit()
00045 {
00046 ConnectionBasedNodelet::onInit();
00047 tf_success_.reset(new SeriesedBoolean(30));
00048 listener_ = TfListenerSingleton::getInstance();
00049 double vital_rate;
00050 pnh_->param("vital_rate", vital_rate, 1.0);
00051 vital_checker_.reset(
00052 new jsk_topic_tools::VitalChecker(1 / vital_rate));
00053
00054 diagnostic_updater_.reset(new diagnostic_updater::Updater);
00055 diagnostic_updater_->setHardwareID(getName());
00056 diagnostic_updater_->add(
00057 getName() + "::PlaneRejector",
00058 boost::bind(
00059 &PlaneRejector::updateDiagnosticsPlaneRejector,
00060 this, _1));
00061 if (!pnh_->getParam("processing_frame_id", processing_frame_id_)) {
00062 JSK_NODELET_FATAL("You need to specify ~processing_frame_id");
00063 return;
00064 }
00065
00066 std::vector<double> reference_axis;
00067 if (!jsk_topic_tools::readVectorParameter(
00068 *pnh_, "reference_axis", reference_axis)) {
00069 JSK_NODELET_FATAL("you need to specify ~reference_axis");
00070 return;
00071 }
00072 else if (reference_axis.size() != 3){
00073 JSK_NODELET_FATAL("~reference_axis is not 3 length vector");
00074 return;
00075 }
00076 else {
00077 pointFromVectorToVector(reference_axis, reference_axis_);
00078 reference_axis_.normalize();
00079 }
00080
00081 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00082 dynamic_reconfigure::Server<Config>::CallbackType f =
00083 boost::bind (&PlaneRejector::configCallback, this, _1, _2);
00084 srv_->setCallback (f);
00085
00086 polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(
00087 *pnh_, "output_polygons", 1);
00088 coefficients_pub_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00089 *pnh_, "output_coefficients", 1);
00090
00091 diagnostics_timer_ = pnh_->createTimer(
00092 ros::Duration(1.0),
00093 boost::bind(&PlaneRejector::updateDiagnostics,
00094 this,
00095 _1));
00096
00097 }
00098
00099 void PlaneRejector::subscribe()
00100 {
00101 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00102 sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00103 sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00104 sync_->connectInput(sub_polygons_, sub_coefficients_);
00105 sync_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2));
00106 }
00107
00108 void PlaneRejector::unsubscribe()
00109 {
00110 sub_polygons_.unsubscribe();
00111 sub_coefficients_.unsubscribe();
00112 }
00113
00114 void PlaneRejector::updateDiagnosticsPlaneRejector(
00115 diagnostic_updater::DiagnosticStatusWrapper &stat)
00116 {
00117 bool alivep = vital_checker_->isAlive();
00118
00119 if (alivep) {
00120 if (tf_success_->getValue()) {
00121 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00122 "PlaneRejector running");
00123 }
00124 else {
00125 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00126 "failed to tf transform");
00127 }
00128 stat.add("Input planes (Avg.)", input_plane_counter_.mean());
00129 stat.add("Rejected Planes (Avg.)", rejected_plane_counter_.mean());
00130 stat.add("Passed Planes (Avg.)", passed_plane_counter_.mean());
00131 stat.add("Angular Threahold", angle_thr_);
00132 stat.add("Reference Axis",
00133 (boost::format("[%f, %f, %f]")
00134 % (reference_axis_[0])
00135 % (reference_axis_[1])
00136 % (reference_axis_[2])).str());
00137 stat.add("Processing Frame ID", processing_frame_id_);
00138 }
00139 else {
00140 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00141 "PlaneRejector not running");
00142 }
00143
00144 }
00145
00146 void PlaneRejector::updateDiagnostics(const ros::TimerEvent& event)
00147 {
00148 boost::mutex::scoped_lock lock(mutex_);
00149 diagnostic_updater_->update();
00150 }
00151
00152 void PlaneRejector::configCallback (Config &config, uint32_t level)
00153 {
00154 boost::mutex::scoped_lock lock(mutex_);
00155 angle_thr_ = config.angle_thr;
00156 }
00157
00158 void PlaneRejector::reject(
00159 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
00160 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
00161 {
00162 boost::mutex::scoped_lock lock(mutex_);
00163 vital_checker_->poke();
00164 jsk_recognition_msgs::PolygonArray result_polygons;
00165 jsk_recognition_msgs::ModelCoefficientsArray result_coefficients;
00166 result_polygons.header = polygons->header;
00167 result_coefficients.header = coefficients->header;
00168 input_plane_counter_.add(polygons->polygons.size());
00169 int rejected_plane_counter = 0;
00170 int passed_plane_counter = 0;
00171 for (size_t i = 0; i < polygons->polygons.size(); i++) {
00172 geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
00173 PCLModelCoefficientMsg coefficient = coefficients->coefficients[i];
00174
00175 if (listener_->canTransform(coefficient.header.frame_id,
00176 processing_frame_id_,
00177 coefficient.header.stamp)) {
00178 tf_success_->addValue(true);
00179 geometry_msgs::Vector3Stamped plane_axis;
00180 plane_axis.header = coefficient.header;
00181 plane_axis.vector.x = coefficient.values[0];
00182 plane_axis.vector.y = coefficient.values[1];
00183 plane_axis.vector.z = coefficient.values[2];
00184 geometry_msgs::Vector3Stamped transformed_plane_axis;
00185 listener_->transformVector(processing_frame_id_,
00186 plane_axis,
00187 transformed_plane_axis);
00188 Eigen::Vector3d eigen_transformed_plane_axis;
00189 tf::vectorMsgToEigen(transformed_plane_axis.vector,
00190 eigen_transformed_plane_axis);
00191 double ang = acos(eigen_transformed_plane_axis.normalized().dot(reference_axis_));
00192 if (ang < angle_thr_) {
00193 ++passed_plane_counter;
00194 result_polygons.polygons.push_back(polygons->polygons[i]);
00195 result_coefficients.coefficients.push_back(coefficient);
00196 }
00197 else {
00198 ++rejected_plane_counter;
00199 }
00200 }
00201 else {
00202 tf_success_->addValue(false);
00203 }
00204 }
00205 rejected_plane_counter_.add(rejected_plane_counter);
00206 passed_plane_counter_.add(passed_plane_counter);
00207 polygons_pub_.publish(result_polygons);
00208 coefficients_pub_.publish(result_coefficients);
00209 diagnostic_updater_->update();
00210 }
00211
00212 }
00213
00214 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PlaneRejector, nodelet::Nodelet);