ROS node class. More...
#include <map_merge_node.h>
Classes | |
struct | MapSubscription |
Public Member Functions | |
void | discovery () |
Initiates discovery of new robots (maps) under current ROS core. More... | |
std::vector< PointCloudConstPtr > | getMaps () |
Get currently stored maps. More... | |
std::vector< Eigen::Matrix4f > | getTransforms () |
Get currently stored transforms. For each map there should be a transform between map and global reference frame. More... | |
void | mapCompositing () |
Composes and publishes the global map based on estimated transformations. More... | |
MapMerge3d () | |
void | transformsEstimation () |
Estimates transformations between maps. More... | |
Private Member Functions | |
bool | isRobotMapTopic (const ros::master::TopicInfo &topic) |
void | mapUpdate (const PointCloud::ConstPtr &msg, MapSubscription &subscription) |
void | publishTF () |
std::string | robotNameFromTopic (const std::string &topic) |
Private Attributes | |
double | compositing_rate_ |
ros::Timer | compositing_timer_ |
double | discovery_rate_ |
ros::Timer | discovery_timer_ |
double | estimation_rate_ |
ros::Timer | estimation_timer_ |
MapMergingParams | map_merge_params_ |
ros::Publisher | merged_map_publisher_ |
ros::NodeHandle | node_ |
std::string | robot_map_topic_ |
std::string | robot_namespace_ |
std::unordered_map< std::string, MapSubscription * > | robots_ |
std::forward_list< MapSubscription > | subscriptions_ |
std::mutex | subscriptions_mutex_ |
size_t | subscriptions_size_ |
std::atomic_flag | tf_current_flag_ |
tf2_ros::TransformBroadcaster | tf_publisher_ |
std::thread | tf_thread_ |
std::vector< geometry_msgs::TransformStamped > | tf_transforms_ |
std::vector< Eigen::Matrix4f > | transforms_ |
std::mutex | transforms_mutex_ |
std::string | world_frame_ |
ROS node class.
Runs robot discovery, transforms estimation and map compositing at predefined rates (from ROS parameters). Does not spin on its own.
Definition at line 32 of file map_merge_node.h.
map_merge_3d::MapMerge3d::MapMerge3d | ( | ) |
void map_merge_3d::MapMerge3d::discovery | ( | ) |
Initiates discovery of new robots (maps) under current ROS core.
When new maps topics are found, there are added for merging. This function is thread-safe
std::vector<PointCloudConstPtr> map_merge_3d::MapMerge3d::getMaps | ( | ) |
Get currently stored maps.
This function is thread-safe
std::vector<Eigen::Matrix4f> map_merge_3d::MapMerge3d::getTransforms | ( | ) |
Get currently stored transforms. For each map there should be a transform between map and global reference frame.
This function is thread-safe
|
private |
void map_merge_3d::MapMerge3d::mapCompositing | ( | ) |
Composes and publishes the global map based on estimated transformations.
This function is thread-safe
|
private |
|
private |
|
private |
void map_merge_3d::MapMerge3d::transformsEstimation | ( | ) |
Estimates transformations between maps.
This function is thread-safe
|
private |
Definition at line 45 of file map_merge_node.h.
|
private |
Definition at line 57 of file map_merge_node.h.
|
private |
Definition at line 46 of file map_merge_node.h.
|
private |
Definition at line 58 of file map_merge_node.h.
|
private |
Definition at line 47 of file map_merge_node.h.
|
private |
Definition at line 59 of file map_merge_node.h.
|
private |
Definition at line 52 of file map_merge_node.h.
|
private |
Definition at line 55 of file map_merge_node.h.
|
private |
Definition at line 42 of file map_merge_node.h.
|
private |
Definition at line 48 of file map_merge_node.h.
|
private |
Definition at line 49 of file map_merge_node.h.
|
private |
Definition at line 68 of file map_merge_node.h.
|
private |
Definition at line 70 of file map_merge_node.h.
|
private |
Definition at line 72 of file map_merge_node.h.
|
private |
Definition at line 71 of file map_merge_node.h.
|
private |
Definition at line 64 of file map_merge_node.h.
|
private |
Definition at line 62 of file map_merge_node.h.
|
private |
Definition at line 63 of file map_merge_node.h.
|
private |
Definition at line 61 of file map_merge_node.h.
|
private |
Definition at line 74 of file map_merge_node.h.
|
private |
Definition at line 75 of file map_merge_node.h.
|
private |
Definition at line 50 of file map_merge_node.h.