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
00038 #include "jsk_pcl_ros/polygon_array_distance_likelihood.h"
00039 #include "jsk_pcl_ros/tf_listener_singleton.h"
00040 #include "jsk_pcl_ros/geo_util.h"
00041 #include "jsk_pcl_ros/pcl_conversion_util.h"
00042
00043 namespace jsk_pcl_ros
00044 {
00045 void PolygonArrayDistanceLikelihood::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
00049 JSK_ROS_ERROR("You need to specify ~target_frame_id");
00050 return;
00051 }
00052 pnh_->param("tf_queue_size", tf_queue_size_, 10);
00053 tf_listener_ = TfListenerSingleton::getInstance();
00054 pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
00055 }
00056
00057 void PolygonArrayDistanceLikelihood::subscribe()
00058 {
00059 sub_.subscribe(*pnh_, "input", 10);
00060 tf_filter_.reset(new tf::MessageFilter<jsk_recognition_msgs::PolygonArray>(
00061 sub_,
00062 *tf_listener_,
00063 target_frame_id_,
00064 tf_queue_size_));
00065 tf_filter_->registerCallback(
00066 boost::bind(&PolygonArrayDistanceLikelihood::likelihood, this, _1));
00067 }
00068
00069 void PolygonArrayDistanceLikelihood::unsubscribe()
00070 {
00071 sub_.unsubscribe();
00072 }
00073
00074 void PolygonArrayDistanceLikelihood::likelihood(
00075 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00076 {
00077 boost::mutex::scoped_lock lock(mutex_);
00078 jsk_recognition_msgs::PolygonArray new_msg(*msg);
00079
00080 try
00081 {
00082
00083
00084
00085 tf::StampedTransform transform;
00086 tf_listener_->lookupTransform(
00087 msg->header.frame_id, target_frame_id_, msg->header.stamp, transform);
00088 Eigen::Affine3f pose;
00089 tf::transformTFToEigen(transform, pose);
00090 Eigen::Vector3f p(pose.translation());
00091
00092 double min_distance = DBL_MAX;
00093 double max_distance = - DBL_MAX;
00094 std::vector<double> distances;
00095 for (size_t i = 0; i < msg->polygons.size(); i++) {
00096 Polygon::Ptr polygon = Polygon::fromROSMsgPtr(msg->polygons[i].polygon);
00097 double distance;
00098 polygon->nearestPoint(p, distance);
00099 min_distance = std::min(distance, min_distance);
00100 max_distance = std::max(distance, max_distance);
00101 distances.push_back(distance);
00102 }
00103
00104
00105 for (size_t i = 0; i < distances.size(); i++) {
00106
00107
00108 double likelihood = 1 / (1 + distances[i] * distances[i]);
00109
00110 if (msg->likelihood.size() == 0) {
00111 new_msg.likelihood.push_back(likelihood);
00112 }
00113 else {
00114 new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
00115 }
00116 }
00117 pub_.publish(new_msg);
00118 }
00119 catch (...)
00120 {
00121 JSK_NODELET_ERROR("Unknown transform error");
00122 }
00123
00124 }
00125 }
00126
00127 #include <pluginlib/class_list_macros.h>
00128 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PolygonArrayDistanceLikelihood,
00129 nodelet::Nodelet);