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 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros_utils/polygon_magnifier.h"
00038 #include "jsk_recognition_utils/geo_util.h"
00039 
00040 namespace jsk_pcl_ros_utils
00041 {
00042   void PolygonMagnifier::onInit()
00043   {
00044     DiagnosticNodelet::onInit();
00045     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00046     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00047       boost::bind (&PolygonMagnifier::configCallback, this, _1, _2);
00048     srv_->setCallback (f);
00049 
00050     pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
00051     onInitPostProcess();
00052   }
00053 
00054   void PolygonMagnifier::subscribe()
00055   {
00056     sub_ = pnh_->subscribe("input", 1, &PolygonMagnifier::magnify, this);
00057   }
00058 
00059   void PolygonMagnifier::unsubscribe()
00060   {
00061     sub_.shutdown();
00062   }
00063 
00064   void PolygonMagnifier::configCallback(Config &config, uint32_t level)
00065   {
00066     boost::mutex::scoped_lock lock(mutex_);
00067     use_scale_factor_ = config.use_scale_factor;
00068     magnify_distance_ = config.magnify_distance;
00069     magnify_scale_factor_ = config.magnify_scale_factor;
00070   }
00071 
00072   void PolygonMagnifier::magnify(
00073     const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00074   {
00075     boost::mutex::scoped_lock lock(mutex_);
00076     vital_checker_->poke();
00077 
00078     jsk_recognition_msgs::PolygonArray ret_polygon_array = *msg;
00079 
00080     for (size_t i = 0; i < msg->polygons.size(); i++) {
00081       jsk_recognition_utils::ConvexPolygon poly =
00082         jsk_recognition_utils::ConvexPolygon::fromROSMsg(msg->polygons[i].polygon);
00083 
00084       jsk_recognition_utils::ConvexPolygon::Ptr magnified_poly;
00085       if (use_scale_factor_) magnified_poly = poly.magnify(magnify_scale_factor_);
00086       else                   magnified_poly = poly.magnifyByDistance(magnify_distance_);
00087 
00088       if (!magnified_poly->isConvex()) {
00089         ROS_WARN("Magnified polygon %ld is not convex.", i);
00090       }
00091 
00092       ret_polygon_array.polygons[i].polygon = magnified_poly->toROSMsg();
00093     }
00094     pub_.publish(ret_polygon_array);
00095   }
00096 }
00097 
00098 #include <pluginlib/class_list_macros.h>
00099 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PolygonMagnifier, nodelet::Nodelet);