Class EsdfServer

Inheritance Relationships

Base Type

Class Documentation

class EsdfServer : public voxblox::TsdfServer

Public Functions

EsdfServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private)
EsdfServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private, const EsdfMap::Config &esdf_config, const EsdfIntegrator::Config &esdf_integrator_config, const TsdfMap::Config &tsdf_config, const TsdfIntegratorBase::Config &tsdf_integrator_config)
virtual ~EsdfServer()
bool generateEsdfCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void publishAllUpdatedEsdfVoxels()
virtual void publishSlices()
void publishTraversable()
virtual void updateMesh()

Incremental update.

virtual void publishPointclouds()
virtual void newPoseCallback(const Transformation &T_G_C)
virtual void publishMap(const bool reset_remote_map = false)
virtual bool saveMap(const std::string &file_path)
virtual bool loadMap(const std::string &file_path)
void updateEsdf()

Call updateMesh if you want everything updated; call this specifically if you don’t want the mesh or visualization.

void updateEsdfBatch(bool full_euclidean = false)
void esdfMapCallback(const voxblox_msgs::Layer &layer_msg)
std::shared_ptr<EsdfMap> getEsdfMapPtr()
std::shared_ptr<const EsdfMap> getEsdfMapPtr() const
bool getClearSphere() const
void setClearSphere(bool clear_sphere_for_planning)
float getEsdfMaxDistance() const
void setEsdfMaxDistance(float max_distance)
float getTraversabilityRadius() const
void setTraversabilityRadius(float traversability_radius)
void disableIncrementalUpdate()

These are for enabling or disabling incremental update of the ESDF.

Use carefully.

void enableIncrementalUpdate()
virtual void clear()

CLEARS THE ENTIRE MAP!

Protected Functions

void setupRos()

Sets up publishing and subscribing.

Should only be called from constructor.

Protected Attributes

ros::Publisher esdf_pointcloud_pub_
ros::Publisher esdf_slice_pub_
ros::Publisher traversable_pub_
ros::Publisher esdf_map_pub_

Publish the complete map for other nodes to consume.

ros::Subscriber esdf_map_sub_

Subscriber to subscribe to another node generating the map.

ros::ServiceServer generate_esdf_srv_

Services.

bool clear_sphere_for_planning_
bool publish_esdf_map_
bool publish_traversable_
float traversability_radius_
bool incremental_update_
std::shared_ptr<EsdfMap> esdf_map_
std::unique_ptr<EsdfIntegrator> esdf_integrator_