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/polygon_flipper.h"
00038 #include "jsk_pcl_ros/pcl_conversion_util.h"
00039 #include <algorithm>
00040 #include <iterator>
00041
00042 namespace jsk_pcl_ros
00043 {
00044 void PolygonFlipper::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 if (!pnh_->getParam("sensor_frame", sensor_frame_)) {
00048 JSK_NODELET_FATAL("no ~sensor_frame is specified");
00049 return;
00050 }
00051 tf_listener_ = TfListenerSingleton::getInstance();
00052 pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
00053 *pnh_, "output/polygons", 1);
00054 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00055 *pnh_, "output/indices", 1);
00056 pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00057 *pnh_, "output/coefficients", 1);
00058 }
00059
00060 void PolygonFlipper::subscribe()
00061 {
00062 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00063 sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
00064 sub_indices_.subscribe(*pnh_, "input/indices", 1);
00065 sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00066 sync_->connectInput(sub_polygons_, sub_indices_, sub_coefficients_);
00067 sync_->registerCallback(boost::bind(&PolygonFlipper::flip, this, _1, _2, _3));
00068 }
00069
00070 void PolygonFlipper::unsubscribe()
00071 {
00072 sub_polygons_.unsubscribe();
00073 sub_coefficients_.unsubscribe();
00074 }
00075
00076 void PolygonFlipper::flip(
00077 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg,
00078 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00079 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00080 {
00081 vital_checker_->poke();
00082 if (polygons_msg->polygons.size() != coefficients_msg->coefficients.size()) {
00083 JSK_NODELET_ERROR("The size of polygons and coefficients are not same");
00084 return;
00085 }
00086 jsk_recognition_msgs::PolygonArray flipped_polygons;
00087 jsk_recognition_msgs::ModelCoefficientsArray flipped_coefficients;
00088 jsk_recognition_msgs::ClusterPointIndices flipped_indices;
00089 flipped_polygons.header = polygons_msg->header;
00090 flipped_coefficients.header = coefficients_msg->header;
00091 flipped_indices.header = indices_msg->header;
00092 try {
00093 for (size_t i = 0; i < polygons_msg->polygons.size(); i++) {
00094 geometry_msgs::PolygonStamped target_polygon = polygons_msg->polygons[i];
00095 PCLModelCoefficientMsg target_coefficients = coefficients_msg->coefficients[i];
00096 PCLIndicesMsg target_indices = indices_msg->cluster_indices[i];
00097 tf::StampedTransform tf_transform
00098 = lookupTransformWithDuration(
00099 tf_listener_, target_coefficients.header.frame_id,
00100 sensor_frame_, target_coefficients.header.stamp,
00101 ros::Duration(1.0));
00102 Eigen::Affine3f sensor_transform;
00103 tf::transformTFToEigen(tf_transform, sensor_transform);
00104 {
00105
00106 ConvexPolygon convex = ConvexPolygon::fromROSMsg(target_polygon.polygon);
00107 Eigen::Vector3f polygon_normal = convex.getNormal();
00108 if (polygon_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
00109 < 0) {
00110 geometry_msgs::PolygonStamped flipped_polygon;
00111 std::reverse_copy(
00112 target_polygon.polygon.points.begin(),
00113 target_polygon.polygon.points.end(),
00114 std::back_inserter(flipped_polygon.polygon.points));
00115 flipped_polygon.header = target_polygon.header;
00116 flipped_polygons.polygons.push_back(flipped_polygon);
00117 }
00118 else {
00119 flipped_polygons.polygons.push_back(target_polygon);
00120 }
00121 }
00122
00123 {
00124
00125 Eigen::Vector3f local_normal(target_coefficients.values[0],
00126 target_coefficients.values[1],
00127 target_coefficients.values[2]);
00128 if (local_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
00129 < 0) {
00130 PCLModelCoefficientMsg the_flipped_coefficients;
00131 PCLIndicesMsg the_flipped_indices;
00132 for (size_t j = 0; j < target_coefficients.values.size(); j++) {
00133 the_flipped_coefficients.values.push_back(
00134 - target_coefficients.values[j]);
00135 }
00136 std::reverse_copy(target_indices.indices.begin(), target_indices.indices.end(),
00137 std::back_inserter(the_flipped_indices.indices));
00138 the_flipped_coefficients.header = target_coefficients.header;
00139 the_flipped_indices.header = target_indices.header;
00140 flipped_coefficients.coefficients.push_back(the_flipped_coefficients);
00141
00142 flipped_indices.cluster_indices.push_back(the_flipped_indices);
00143
00144 }
00145 else {
00146
00147 flipped_coefficients.coefficients.push_back(target_coefficients);
00148 flipped_indices.cluster_indices.push_back(target_indices);
00149 }
00150 }
00151 }
00152 pub_polygons_.publish(flipped_polygons);
00153 pub_coefficients_.publish(flipped_coefficients);
00154 pub_indices_.publish(flipped_indices);
00155 }
00156 catch (tf2::TransformException& e) {
00157 JSK_NODELET_ERROR("Failed to lookup transformation: %s", e.what());
00158 }
00159 }
00160 }
00161
00162 #include <pluginlib/class_list_macros.h>
00163 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PolygonFlipper, nodelet::Nodelet);