Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added Tf publisher #30

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 16 additions & 0 deletions map_merge/include/map_merge/map_merge.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,10 @@

#include <combine_grids/merging_pipeline.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/TransformStamped.h>
#include <map_msgs/OccupancyGridUpdate.h>
#include <nav_msgs/OccupancyGrid.h>
#include <tf2_ros/transform_broadcaster.h>
#include <ros/ros.h>
#include <boost/thread.hpp>

Expand All @@ -56,6 +58,7 @@ struct MapSubscription {
// protects consistency of writable_map and readonly_map
// also protects reads and writes of shared_ptrs
std::mutex mutex;
std::string map_frame;

geometry_msgs::Transform initial_pose;
nav_msgs::OccupancyGrid::Ptr writable_map;
Expand All @@ -80,6 +83,7 @@ class MapMerge
std::string robot_namespace_;
std::string world_frame_;
bool have_initial_poses_;
bool publish_tf = true;

// publishing
ros::Publisher merged_map_publisher_;
Expand All @@ -92,6 +96,18 @@ class MapMerge
combine_grids::MergingPipeline pipeline_;
std::mutex pipeline_mutex_;

// publishing tfs
std::vector<std::string> map_frames_;
std::vector<geometry_msgs::TransformStamped> tf_transforms_;
tf2_ros::TransformBroadcaster tf_publisher_;
std::thread tf_thread_; // tf needs it own thread
std::atomic_flag tf_current_flag_; // whether tf_transforms_ are up to date
// with transforms_


void publishTF();
std::vector<geometry_msgs::TransformStamped> StampTransforms(const std::vector<geometry_msgs::Transform>, const std::string& frame);

std::string robotNameFromTopic(const std::string& topic);
bool isRobotMapTopic(const ros::master::TopicInfo& topic);
bool getInitPose(const std::string& name, geometry_msgs::Transform& pose);
Expand Down
5 changes: 4 additions & 1 deletion map_merge/src/combine_grids/merging_pipeline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,9 +214,12 @@ std::vector<geometry_msgs::Transform> MergingPipeline::getTransforms() const
std::vector<geometry_msgs::Transform> result;
result.reserve(transforms_.size());

geometry_msgs::Transform identity_quaternion;
identity_quaternion.rotation.w = 1;

for (auto& transform : transforms_) {
if (transform.empty()) {
result.emplace_back();
result.emplace_back(identity_quaternion);
continue;
}

Expand Down
59 changes: 57 additions & 2 deletions map_merge/src/map_merge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,14 @@ MapMerge::MapMerge() : subscriptions_size_(0)
robot_map_updates_topic_, "map_updates");
private_nh.param<std::string>("robot_namespace", robot_namespace_, "");
private_nh.param<std::string>("merged_map_topic", merged_map_topic, "map");
private_nh.param<std::string>("world_frame", world_frame_, "world");
private_nh.param<std::string>("world_frame", world_frame_, "map");
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is this intended?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, but it is because in my opinion each robot map should have the namespace of the robot, and then, the global map, just be called map.
But it is just how I imagine it. I can revert this change before the pull request.

private_nh.param("publish_tf", publish_tf, true);

/* publishing */
merged_map_publisher_ =
node_.advertise<nav_msgs::OccupancyGrid>(merged_map_topic, 50, true);
tf_current_flag_.clear();

}

/*
Expand Down Expand Up @@ -186,22 +189,29 @@ void MapMerge::mapMerging()

void MapMerge::poseEstimation()
{
bool new_transform = false;
ROS_DEBUG("Grid pose estimation started.");
std::vector<nav_msgs::OccupancyGridConstPtr> grids;

grids.reserve(subscriptions_size_);
{
map_frames_.clear();
boost::shared_lock<boost::shared_mutex> lock(subscriptions_mutex_);
for (auto& subscription : subscriptions_) {
std::lock_guard<std::mutex> s_lock(subscription.mutex);
grids.push_back(subscription.readonly_map);
map_frames_.push_back(subscription.map_frame);
}
}

std::lock_guard<std::mutex> lock(pipeline_mutex_);
pipeline_.feed(grids.begin(), grids.end());
// TODO allow user to change feature type
pipeline_.estimateTransforms(combine_grids::FeatureType::AKAZE,
new_transform = pipeline_.estimateTransforms(combine_grids::FeatureType::AKAZE,
confidence_threshold_);
if (new_transform){
tf_current_flag_.clear();
}
}

void MapMerge::fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg,
Expand All @@ -215,6 +225,7 @@ void MapMerge::fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg,
return;
}

subscription.map_frame = msg->header.frame_id;
subscription.readonly_map = msg;
subscription.writable_map = nullptr;
}
Expand Down Expand Up @@ -378,6 +389,41 @@ void MapMerge::executeposeEstimation()
}
}

void MapMerge::publishTF()
{
if (!tf_current_flag_.test_and_set()) {
// need to recalculate stored transforms
auto transforms = pipeline_.getTransforms(); // this is thread-safe access
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is not a thread-safe access AFAIK

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It think this may be the cause of the crash you experienced.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok! I'll have a look to this.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have checked with TSan, and as you said, there was an issue there.
I have added a mutex to protect it.
With TSan I still have other warnings, however, I can't find the issue and I haven't experienced any other crashes.

//auto maps = getMaps();
tf_transforms_ = StampTransforms(transforms, world_frame_);
}
if (tf_transforms_.empty()) {
return;
}

// no locking. tf_transforms_ is always accessed only from tf thread
for (auto& transform : tf_transforms_) {
tf_publisher_.sendTransform(transform);
}
}

std::vector<geometry_msgs::TransformStamped> MapMerge::StampTransforms(const std::vector<geometry_msgs::Transform> transforms_, const std::string& frame)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

functions start with lowercase letter. this function should be static inline non-member or static member as it does not access any member variables. names with trailing underscore indicate member variables and should not be used as arguments.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This function actually uses two member variables, which allow proper map naming. I changed the name of the transforms parameter not to confuse.
So should I leave this function as a member function as it uses two member variables or should I keep it static and pass the variables as parameters?

{
std::vector<geometry_msgs::TransformStamped> output;
output.reserve(transforms_.size());
int ii = 0;
for (auto transform : transforms_){
geometry_msgs::TransformStamped tf_stamped;
tf_stamped.transform = transform;
tf_stamped.child_frame_id = map_frames_[ii];
tf_stamped.header.frame_id = "world_frame_";
tf_stamped.header.stamp = ros::Time::now();
output.push_back(tf_stamped);
ii++;
}
return output;
}

/*
* spin()
*/
Expand All @@ -387,6 +433,15 @@ void MapMerge::spin()
std::thread merging_thr([this]() { executemapMerging(); });
std::thread subscribing_thr([this]() { executetopicSubscribing(); });
std::thread estimation_thr([this]() { executeposeEstimation(); });
if (publish_tf) {
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

could we make this similar to those above?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done, I should have done it your way since the beginning.

tf_thread_ = std::thread([this]() {
ros::Rate rate(30.0);
while (node_.ok()) {
publishTF();
rate.sleep();
}
});
}
ros::spin();
estimation_thr.join();
merging_thr.join();
Expand Down