Go to the documentation of this file.
43 #include <sensor_msgs/PointCloud2.h>
51 class PointCloudOctomapUpdater :
public OccupancyMapUpdater
60 void start()
override;
66 virtual void updateMask(
const sensor_msgs::PointCloud2& cloud,
const Eigen::Vector3d& sensor_origin,
67 std::vector<int>& mask);
78 std::shared_ptr<tf2_ros::TransformListener>
tf_listener_;
100 std::unique_ptr<point_containment_filter::ShapeMask>
shape_mask_;
101 std::vector<int>
mask_;
void forgetShape(ShapeHandle handle) override
ros::Publisher filtered_cloud_publisher_
~PointCloudOctomapUpdater() override
std::string point_cloud_topic_
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
std::unique_ptr< point_containment_filter::ShapeMask > shape_mask_
ros::NodeHandle private_nh_
message_filters::Subscriber< sensor_msgs::PointCloud2 > * point_cloud_subscriber_
bool initialize() override
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
bool getShapeTransform(ShapeHandle h, Eigen::Isometry3d &transform) const
PointCloudOctomapUpdater()
ros::Time last_update_time_
std::string filtered_cloud_topic_
bool setParams(XmlRpc::XmlRpcValue ¶ms) override
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > * point_cloud_filter_
std::shared_ptr< const Shape > ShapeConstPtr
virtual void updateMask(const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector3d &sensor_origin, std::vector< int > &mask)
unsigned int point_subsample_
void cloudMsgCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
perception
Author(s): Ioan Sucan
, Jon Binney , Suat Gedikli
autogenerated on Mon May 27 2024 02:27:57