Class TsdfServer

Inheritance Relationships

Derived Types

Class Documentation

class TsdfServer

Subclassed by voxblox::EsdfServer, voxblox::IntensityServer

Public Functions

TsdfServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private)
TsdfServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private, const TsdfMap::Config &config, const TsdfIntegratorBase::Config &integrator_config)
virtual ~TsdfServer()
void getServerConfigFromRosParam(const ros::NodeHandle &nh_private)
void insertPointcloud(const sensor_msgs::PointCloud2::Ptr &pointcloud)
void insertFreespacePointcloud(const sensor_msgs::PointCloud2::Ptr &pointcloud)
virtual void processPointCloudMessageAndInsert(const sensor_msgs::PointCloud2::Ptr &pointcloud_msg, const Transformation &T_G_C, const bool is_freespace_pointcloud)
void integratePointcloud(const Transformation &T_G_C, const Pointcloud &ptcloud_C, const Colors &colors, const bool is_freespace_pointcloud = false)
virtual void newPoseCallback(const Transformation&)
void publishAllUpdatedTsdfVoxels()
void publishTsdfSurfacePoints()
void publishTsdfOccupiedNodes()
virtual void publishSlices()
virtual void updateMesh()

Incremental update.

virtual bool generateMesh()

Batch update.

virtual void publishPointclouds()
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)
bool clearMapCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool saveMapCallback(voxblox_msgs::FilePath::Request &request, voxblox_msgs::FilePath::Response &response)
bool loadMapCallback(voxblox_msgs::FilePath::Request &request, voxblox_msgs::FilePath::Response &response)
bool generateMeshCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool publishPointcloudsCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool publishTsdfMapCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void updateMeshEvent(const ros::TimerEvent &event)
std::shared_ptr<TsdfMap> getTsdfMapPtr()
double getSliceLevel() const

Accessors for setting and getting parameters.

void setSliceLevel(double slice_level)
bool setPublishSlices() const
void setPublishSlices(const bool publish_slices)
void setWorldFrame(const std::string &world_frame)
std::string getWorldFrame() const
virtual void clear()

CLEARS THE ENTIRE MAP!

void tsdfMapCallback(const voxblox_msgs::Layer &layer_msg)

Overwrites the layer with what’s coming from the topic!

Protected Functions

bool getNextPointcloudFromQueue(std::queue<sensor_msgs::PointCloud2::Ptr> *queue, sensor_msgs::PointCloud2::Ptr *pointcloud_msg, Transformation *T_G_C)

Gets the next pointcloud that has an available transform to process from the queue.

Protected Attributes

ros::NodeHandle nh_
ros::NodeHandle nh_private_
bool verbose_
std::string world_frame_

Global/map coordinate frame.

Will always look up TF transforms to this frame.

std::string icp_corrected_frame_

Name of the ICP corrected frame.

Publishes TF and transform topic to this if ICP on.

std::string pose_corrected_frame_

Name of the pose in the ICP correct Frame.

double max_block_distance_from_body_

Delete blocks that are far from the system to help manage memory.

double slice_level_

Pointcloud visualization settings.

bool use_freespace_pointcloud_

If the system should subscribe to a pointcloud giving points in freespace.

std::string mesh_filename_

Mesh output settings.

Mesh is only written to file if mesh_filename_ is not empty.

ColorMode color_mode_

How to color the mesh.

std::unique_ptr<ColorMap> color_map_

Colormap to use for intensity pointclouds.

ros::Duration min_time_between_msgs_

Will throttle to this message rate.

bool publish_tsdf_info_

What output information to publish.

bool publish_slices_
bool publish_pointclouds_
bool publish_tsdf_map_
bool cache_mesh_

Whether to save the latest mesh message sent (for inheriting classes).

bool enable_icp_

Whether to enable ICP corrections.

Every pointcloud coming in will attempt to be matched up to the existing structure using ICP. Requires the initial guess from odometry to already be very good.

bool accumulate_icp_corrections_

If using ICP corrections, whether to store accumulate the corrected transform.

If this is set to false, the transform will reset every iteration.

ros::Subscriber pointcloud_sub_

Data subscribers.

ros::Subscriber freespace_pointcloud_sub_
int pointcloud_queue_size_

Subscriber settings.

ros::Publisher mesh_pub_
ros::Publisher tsdf_pointcloud_pub_
ros::Publisher surface_pointcloud_pub_
ros::Publisher tsdf_slice_pub_
ros::Publisher occupancy_marker_pub_
ros::Publisher icp_transform_pub_
ros::Publisher tsdf_map_pub_

Publish the complete map for other nodes to consume.

ros::Subscriber tsdf_map_sub_

Subscriber to subscribe to another node generating the map.

ros::ServiceServer generate_mesh_srv_
ros::ServiceServer clear_map_srv_
ros::ServiceServer save_map_srv_
ros::ServiceServer load_map_srv_
ros::ServiceServer publish_pointclouds_srv_
ros::ServiceServer publish_tsdf_map_srv_
tf::TransformBroadcaster tf_broadcaster_

Tools for broadcasting TFs.

ros::Timer update_mesh_timer_
std::shared_ptr<TsdfMap> tsdf_map_
std::unique_ptr<TsdfIntegratorBase> tsdf_integrator_
std::shared_ptr<ICP> icp_

ICP matcher.

std::shared_ptr<MeshLayer> mesh_layer_
std::unique_ptr<MeshIntegrator<TsdfVoxel>> mesh_integrator_
voxblox_msgs::Mesh cached_mesh_msg_

Optionally cached mesh message.

Transformer transformer_

Transformer object to keep track of either TF transforms or messages from a transform topic.

std::queue<sensor_msgs::PointCloud2::Ptr> pointcloud_queue_

Queue of incoming pointclouds, in case the transforms can’t be immediately resolved.

std::queue<sensor_msgs::PointCloud2::Ptr> freespace_pointcloud_queue_
ros::Time last_msg_time_ptcloud_
ros::Time last_msg_time_freespace_ptcloud_
Transformation icp_corrected_transform_

Current transform corrections from ICP.