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
00037
00038
00039
00040
00041
00042
00043 #include <geometry_msgs/PolygonStamped.h>
00044 #include <pluginlib/class_list_macros.h>
00045 #include <segbot_sensors/segbot_velodyne_outlier_removal.h>
00046
00047 #include <pcl/io/io.h>
00048 #include "pcl_ros/transforms.h"
00049 #include "pcl_ros/filters/filter.h"
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00072 void
00073 segbot_sensors::Filter::computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
00074 {
00075 PointCloud2 output;
00076
00077 filter (input, indices, output);
00078
00079 PointCloud2::Ptr cloud_tf (new PointCloud2 (output));
00080
00081 if (!tf_output_frame_.empty () && output.header.frame_id != tf_output_frame_)
00082 {
00083 NODELET_DEBUG ("[%s::computePublish] Transforming output dataset from %s to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_output_frame_.c_str ());
00084
00085 PointCloud2 cloud_transformed;
00086 if (!pcl_ros::transformPointCloud (tf_output_frame_, output, cloud_transformed, tf_listener_))
00087 {
00088 NODELET_ERROR ("[%s::computePublish] Error converting output dataset from %s to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_output_frame_.c_str ());
00089 return;
00090 }
00091 cloud_tf.reset (new PointCloud2 (cloud_transformed));
00092 }
00093 if (tf_output_frame_.empty () && output.header.frame_id != tf_input_orig_frame_)
00094
00095 {
00096 NODELET_DEBUG ("[%s::computePublish] Transforming output dataset from %s back to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_input_orig_frame_.c_str ());
00097
00098 PointCloud2 cloud_transformed;
00099 if (!pcl_ros::transformPointCloud (tf_input_orig_frame_, output, cloud_transformed, tf_listener_))
00100 {
00101 NODELET_ERROR ("[%s::computePublish] Error converting output dataset from %s back to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_input_orig_frame_.c_str ());
00102 return;
00103 }
00104 cloud_tf.reset (new PointCloud2 (cloud_transformed));
00105 }
00106
00107
00108 cloud_tf->header.stamp = input->header.stamp;
00109
00110
00111 pub_output_.publish (cloud_tf);
00112 }
00113
00115 void
00116 segbot_sensors::Filter::onInit ()
00117 {
00118
00119 PCLNodelet::onInit ();
00120
00121
00122 bool has_service = false;
00123 if (!child_init (*pnh_, has_service))
00124 {
00125 NODELET_ERROR ("[%s::onInit] Initialization failed.", getName ().c_str ());
00126 return;
00127 }
00128
00129 pub_output_ = pnh_->advertise<PointCloud2> ("output", max_queue_size_);
00130
00131
00132 if (!has_service)
00133 {
00134 srv_ = boost::make_shared <dynamic_reconfigure::Server<segbot_sensors::FilterConfig> > (*pnh_);
00135 dynamic_reconfigure::Server<segbot_sensors::FilterConfig>::CallbackType f = boost::bind (&Filter::config_callback, this, _1, _2);
00136 srv_->setCallback (f);
00137 }
00138
00139
00140 if (use_indices_)
00141 {
00142
00143 sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00144 sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00145
00146 if (approximate_sync_)
00147 {
00148 sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
00149 sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
00150 sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
00151 }
00152 else
00153 {
00154 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
00155 sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
00156 sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
00157 }
00158 }
00159 else
00160
00161 sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, _1, pcl_msgs::PointIndicesConstPtr ()));
00162
00163 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created.", getName ().c_str ());
00164 }
00165
00167 void
00168 segbot_sensors::Filter::config_callback (segbot_sensors::FilterConfig &config, uint32_t level)
00169 {
00170
00171 if (tf_input_frame_ != config.input_frame)
00172 {
00173 tf_input_frame_ = config.input_frame;
00174 NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
00175 }
00176 if (tf_output_frame_ != config.output_frame)
00177 {
00178 tf_output_frame_ = config.output_frame;
00179 NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
00180 }
00181 }
00182
00184 void
00185 segbot_sensors::Filter::input_indices_callback (const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
00186 {
00187
00188 if (pub_output_.getNumSubscribers () <= 0)
00189 return;
00190
00191
00192 if (!isValid (cloud))
00193 {
00194 NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
00195 return;
00196 }
00197
00198 if (indices && !isValid (indices))
00199 {
00200 NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
00201 return;
00202 }
00203
00205 if (indices)
00206 NODELET_DEBUG ("[%s::input_indices_callback]\n"
00207 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00208 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00209 getName ().c_str (),
00210 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00211 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
00212 else
00213 NODELET_DEBUG ("[%s::input_indices_callback] PointCloud with %d data points and frame %s on topic %s received.", getName ().c_str (), cloud->width * cloud->height, cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
00215
00216
00217 tf_input_orig_frame_ = cloud->header.frame_id;
00218 PointCloud2::ConstPtr cloud_tf;
00219 if (!tf_input_frame_.empty () && cloud->header.frame_id != tf_input_frame_)
00220 {
00221 NODELET_DEBUG ("[%s::input_indices_callback] Transforming input dataset from %s to %s.", getName ().c_str (), cloud->header.frame_id.c_str (), tf_input_frame_.c_str ());
00222
00223
00224 PointCloud2 cloud_transformed;
00225 if (!pcl_ros::transformPointCloud (tf_input_frame_, *cloud, cloud_transformed, tf_listener_))
00226 {
00227 NODELET_ERROR ("[%s::input_indices_callback] Error converting input dataset from %s to %s.", getName ().c_str (), cloud->header.frame_id.c_str (), tf_input_frame_.c_str ());
00228 return;
00229 }
00230 cloud_tf = boost::make_shared<PointCloud2> (cloud_transformed);
00231 }
00232 else
00233 cloud_tf = cloud;
00234
00235
00236 IndicesPtr vindices;
00237 if (indices)
00238 vindices.reset (new std::vector<int> (indices->indices));
00239
00240 computePublish (cloud_tf, vindices);
00241 }
00243 bool
00244 segbot_sensors::SegbotVelodyneOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_service)
00245 {
00246
00247 has_service = true;
00248 srv_ = boost::make_shared <dynamic_reconfigure::Server<segbot_sensors::SegbotVelodyneOutlierRemovalConfig> > (nh);
00249 dynamic_reconfigure::Server<segbot_sensors::SegbotVelodyneOutlierRemovalConfig>::CallbackType f =
00250 boost::bind (&SegbotVelodyneOutlierRemoval::config_callback, this, _1, _2);
00251 srv_->setCallback (f);
00252
00253 return (true);
00254 }
00255
00257 void
00258 segbot_sensors::SegbotVelodyneOutlierRemoval::config_callback (segbot_sensors::SegbotVelodyneOutlierRemovalConfig &config, uint32_t level)
00259 {
00260 boost::mutex::scoped_lock lock (mutex_);
00261
00262 footprint_.clear();
00263
00264 bool at_near = true;
00265 float near_range = 0.3f;
00266 for (int angle_idx = 0; angle_idx < 8; ++angle_idx) {
00267
00268 float angle = (angle_idx == 3 || angle_idx == 4) ? config.wire_conduit_angle : config.support_struct_angle;
00269 std::vector<float> ranges;
00270 if (at_near) {
00271 angle += (angle_idx / 2) * M_PI/2;
00272 ranges.push_back(near_range);
00273 ranges.push_back(config.range);
00274 } else {
00275 angle = ((angle_idx + 1) / 2) * M_PI/2 - angle;
00276 ranges.push_back(config.range);
00277 ranges.push_back(near_range);
00278 }
00279 for (int range_idx = 0; range_idx < 2; ++range_idx) {
00280 geometry_msgs::Point p;
00281 p.x = cosf(angle) * ranges[range_idx];
00282 p.y = sinf(angle) * ranges[range_idx];
00283 footprint_.push_back(p);
00284 }
00285 at_near = !at_near;
00286 }
00287
00288
00289 if (!footprint_publisher_) {
00290
00291 footprint_publisher_ = boost::make_shared<ros::Publisher>();
00292 *footprint_publisher_ = getPrivateNodeHandle().advertise<geometry_msgs::PolygonStamped>("footprint", 1, true);
00293 }
00294
00295 geometry_msgs::PolygonStamped polygon_msg;
00296
00297 polygon_msg.header.frame_id = "velodyne";
00298 polygon_msg.header.stamp = ros::Time::now();
00299 polygon_msg.polygon.points.resize(footprint_.size());
00300 for (uint32_t i = 0; i < footprint_.size(); ++i) {
00301 polygon_msg.polygon.points[i].x = footprint_[i].x;
00302 polygon_msg.polygon.points[i].y = footprint_[i].y;
00303 polygon_msg.polygon.points[i].z = 0;
00304 }
00305 footprint_publisher_->publish(polygon_msg);
00306
00307 }
00308
00309 typedef segbot_sensors::SegbotVelodyneOutlierRemoval SegbotVelodyneOutlierRemoval;
00310 PLUGINLIB_EXPORT_CLASS(SegbotVelodyneOutlierRemoval,nodelet::Nodelet);