Go to the documentation of this file.
50 class DepthImageOctomapUpdater :
public OccupancyMapUpdater
58 void start()
override;
64 void depthImageCallback(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
101 std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> >
mesh_filter_;
std::vector< unsigned int > filtered_labels_
image_transport::CameraPublisher pub_model_depth_image_
bool setParams(XmlRpc::XmlRpcValue ¶ms) override
unsigned int image_callback_count_
std::unique_ptr< LazyFreeSpaceUpdater > free_space_updater_
std::string filtered_cloud_topic_
std::vector< float > x_cache_
ros::WallTime last_depth_callback_start_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
ros::Time last_update_time_
bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d &transform) const
double average_callback_dt_
image_transport::ImageTransport input_depth_transport_
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
void forgetShape(ShapeHandle handle) override
image_transport::ImageTransport filtered_label_transport_
std::vector< float > y_cache_
DepthImageOctomapUpdater()
image_transport::ImageTransport filtered_depth_transport_
image_transport::ImageTransport model_depth_transport_
image_transport::CameraPublisher pub_filtered_label_image_
std::shared_ptr< const Shape > ShapeConstPtr
double far_clipping_plane_distance_
std::unique_ptr< mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > > mesh_filter_
bool initialize() override
image_transport::CameraPublisher pub_filtered_depth_image_
void depthImageCallback(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
unsigned int skip_horizontal_pixels_
~DepthImageOctomapUpdater() override
unsigned int skip_vertical_pixels_
double near_clipping_plane_distance_
image_transport::CameraSubscriber sub_depth_image_
perception
Author(s): Ioan Sucan
, Jon Binney , Suat Gedikli
autogenerated on Sat Mar 15 2025 02:26:49