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 #include <jsk_topic_tools/log_utils.h>
00036 #include "jsk_pcl_ros/pointcloud_moveit_filter.h"
00037
00038 namespace jsk_pcl_ros
00039 {
00040 PointCloudMoveitFilter::PointCloudMoveitFilter():
00041 OccupancyMapUpdater("PointCloudMoveitFilter"),
00042 private_nh_("~"),
00043 scale_(1.0),
00044 padding_(0.0),
00045 max_range_(std::numeric_limits<double>::infinity()),
00046 point_subsample_(1),
00047 point_cloud_subscriber_(NULL),
00048 point_cloud_filter_(NULL),
00049 use_color_(false),
00050 keep_organized_(false)
00051 {
00052 }
00053
00054 PointCloudMoveitFilter::~PointCloudMoveitFilter()
00055 {
00056 }
00057
00058 bool PointCloudMoveitFilter::setParams(XmlRpc::XmlRpcValue ¶ms)
00059 {
00060 try
00061 {
00062 if (!params.hasMember("point_cloud_topic"))
00063 return false;
00064 point_cloud_topic_ = static_cast<const std::string&>(params["point_cloud_topic"]);
00065
00066 readXmlParam(params, "max_range", &max_range_);
00067 readXmlParam(params, "padding_offset", &padding_);
00068 readXmlParam(params, "padding_scale", &scale_);
00069 readXmlParam(params, "point_subsample", &point_subsample_);
00070 if (!params.hasMember("filtered_cloud_topic")) {
00071 ROS_ERROR("filtered_cloud_topic is required");
00072 return false;
00073 }
00074 else {
00075 filtered_cloud_topic_ = static_cast<const std::string&>(params["filtered_cloud_topic"]);
00076 }
00077 if (params.hasMember("filtered_cloud_use_color")) {
00078 use_color_ = (bool)params["filtered_cloud_use_color"];
00079 }
00080 if (params.hasMember("filtered_cloud_keep_organized")) {
00081 keep_organized_ = (bool)params["filtered_cloud_keep_organized"];
00082 }
00083 }
00084 catch (XmlRpc::XmlRpcException& ex)
00085 {
00086 ROS_ERROR("XmlRpc Exception: %s", ex.getMessage().c_str());
00087 return false;
00088 }
00089
00090 return true;
00091 }
00092
00093
00094
00095 bool PointCloudMoveitFilter::initialize()
00096 {
00097 tf_ = monitor_->getTFClient();
00098 shape_mask_.reset(new point_containment_filter::ShapeMask());
00099 shape_mask_->setTransformCallback(
00100 boost::bind(&PointCloudMoveitFilter::getShapeTransform, this, _1, _2));
00101 filtered_cloud_publisher_ = private_nh_.advertise<sensor_msgs::PointCloud2>(
00102 filtered_cloud_topic_, 10, false);
00103 return true;
00104 }
00105
00106 bool PointCloudMoveitFilter::getShapeTransform(ShapeHandle h, Eigen::Affine3d &transform) const
00107 {
00108 ShapeTransformCache::const_iterator it = transform_cache_.find(h);
00109 if (it == transform_cache_.end())
00110 {
00111 ROS_ERROR("Internal error. Shape filter handle %u not found", h);
00112 return false;
00113 }
00114 transform = it->second;
00115 return true;
00116 }
00117
00118 ShapeHandle PointCloudMoveitFilter::excludeShape(const shapes::ShapeConstPtr &shape)
00119 {
00120 ShapeHandle h = 0;
00121 if (shape_mask_)
00122 h = shape_mask_->addShape(shape, scale_, padding_);
00123 else
00124 ROS_ERROR("Shape filter not yet initialized!");
00125 return h;
00126 }
00127
00128
00129 void PointCloudMoveitFilter::forgetShape(ShapeHandle handle)
00130 {
00131 if (shape_mask_)
00132 shape_mask_->removeShape(handle);
00133 }
00134
00135
00136 void PointCloudMoveitFilter::start()
00137 {
00138 if (point_cloud_subscriber_)
00139 return;
00140
00141 point_cloud_subscriber_
00142 = new message_filters::Subscriber<sensor_msgs::PointCloud2>(
00143 root_nh_, point_cloud_topic_, 5);
00144 if (tf_ && !monitor_->getMapFrame().empty())
00145 {
00146 point_cloud_filter_
00147 = new tf::MessageFilter<sensor_msgs::PointCloud2>(
00148 *point_cloud_subscriber_, *tf_, monitor_->getMapFrame(), 5);
00149 if (use_color_) {
00150 point_cloud_filter_->registerCallback(
00151 boost::bind(
00152 &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZRGB>,
00153 this, _1));
00154 }
00155 else {
00156 point_cloud_filter_->registerCallback(
00157 boost::bind(
00158 &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZ>,
00159 this, _1));
00160 }
00161 ROS_INFO("Listening to '%s' using message filter with target frame '%s'",
00162 point_cloud_topic_.c_str(),
00163 point_cloud_filter_->getTargetFramesString().c_str());
00164 }
00165 else
00166 {
00167 if (use_color_) {
00168 point_cloud_subscriber_->registerCallback(
00169 boost::bind(
00170 &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZRGB>,
00171 this, _1));
00172 }
00173 else {
00174 point_cloud_subscriber_->registerCallback(
00175 boost::bind(&PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZ>,
00176 this, _1));
00177 }
00178 ROS_INFO("Listening to '%s'", point_cloud_topic_.c_str());
00179 }
00180 }
00181
00182 void PointCloudMoveitFilter::stopHelper()
00183 {
00184 delete point_cloud_filter_;
00185 delete point_cloud_subscriber_;
00186 }
00187
00188 void PointCloudMoveitFilter::stop()
00189 {
00190 stopHelper();
00191 point_cloud_filter_ = NULL;
00192 point_cloud_subscriber_ = NULL;
00193 }
00194
00195 }
00196
00197 #include <class_loader/class_loader.h>
00198 CLASS_LOADER_REGISTER_CLASS(jsk_pcl_ros::PointCloudMoveitFilter, occupancy_map_monitor::OccupancyMapUpdater)