Skip to content

Commit f8b5bd2

Browse files
author
Albert Seligmann
committed
Add method for transforming map tf and pose estimate to a target frame different from the camera frame
1 parent 7282412 commit f8b5bd2

File tree

2 files changed

+82
-8
lines changed

2 files changed

+82
-8
lines changed

ros/include/Node.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,9 @@
2929
#include <opencv2/core/core.hpp>
3030

3131
#include <tf2_ros/transform_broadcaster.h>
32+
#include <tf2_ros/transform_listener.h>
33+
#include <tf2_ros/buffer.h>
34+
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
3235

3336
#include <dynamic_reconfigure/server.h>
3437
#include <orb_slam2_ros/dynamic_reconfigureConfig.h>
@@ -70,7 +73,12 @@ class Node
7073
bool SaveMapSrv (orb_slam2_ros::SaveMap::Request &req, orb_slam2_ros::SaveMap::Response &res);
7174
void LoadOrbParameters (ORB_SLAM2::ORBParameters& parameters);
7275

76+
// initialization Transform listener
77+
boost::shared_ptr<tf2_ros::Buffer> tfBuffer;
78+
boost::shared_ptr<tf2_ros::TransformListener> tfListener;
79+
7380
tf2::Transform TransformFromMat (cv::Mat position_mat);
81+
tf2::Transform TransformToTarget (tf2::Transform tf_in, std::string frame_in, std::string frame_target);
7482
sensor_msgs::PointCloud2 MapPointsToPointCloud (std::vector<ORB_SLAM2::MapPoint*> map_points);
7583

7684
dynamic_reconfigure::Server<orb_slam2_ros::dynamic_reconfigureConfig> dynamic_param_server_;
@@ -89,6 +97,7 @@ class Node
8997

9098
std::string map_frame_id_param_;
9199
std::string camera_frame_id_param_;
100+
std::string target_frame_id_param_;
92101
std::string map_file_name_param_;
93102
std::string voc_file_name_param_;
94103
bool load_map_param_;

ros/src/Node.cc

Lines changed: 73 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ void Node::Init () {
2727
node_handle_.param(name_of_node_+ "/publish_tf", publish_tf_param_, true);
2828
node_handle_.param<std::string>(name_of_node_+ "/pointcloud_frame_id", map_frame_id_param_, "map");
2929
node_handle_.param<std::string>(name_of_node_+ "/camera_frame_id", camera_frame_id_param_, "camera_link");
30+
node_handle_.param<std::string>(name_of_node_+ "/target_frame_id", target_frame_id_param_, "base_link");
3031
node_handle_.param<std::string>(name_of_node_ + "/map_file", map_file_name_param_, "map.bin");
3132
node_handle_.param<std::string>(name_of_node_ + "/voc_file", voc_file_name_param_, "file_not_set");
3233
node_handle_.param(name_of_node_ + "/load_map", load_map_param_, false);
@@ -44,6 +45,10 @@ void Node::Init () {
4445
dynamic_param_callback = boost::bind(&Node::ParamsChangedCallback, this, _1, _2);
4546
dynamic_param_server_.setCallback(dynamic_param_callback);
4647

48+
// Initialization transformation listener
49+
tfBuffer.reset(new tf2_ros::Buffer);
50+
tfListener.reset(new tf2_ros::TransformListener(*tfBuffer));
51+
4752
rendered_image_publisher_ = image_transport_.advertise (name_of_node_+"/debug_image", 1);
4853
if (publish_pointcloud_param_) {
4954
map_points_publisher_ = node_handle_.advertise<sensor_msgs::PointCloud2> (name_of_node_+"/map_points", 1);
@@ -60,7 +65,7 @@ void Node::Update () {
6065
cv::Mat position = orb_slam_->GetCurrentPosition();
6166

6267
if (!position.empty()) {
63-
if(publish_tf_param_){
68+
if (publish_tf_param_){
6469
PublishPositionAsTransform(position);
6570
}
6671

@@ -83,29 +88,89 @@ void Node::PublishMapPoints (std::vector<ORB_SLAM2::MapPoint*> map_points) {
8388
map_points_publisher_.publish (cloud);
8489
}
8590

91+
tf2::Transform Node::TransformToTarget (tf2::Transform tf_in, std::string frame_in, std::string frame_target) {
92+
// Transform tf_in from frame_in to frame_target
93+
tf2::Transform tf_map2orig = tf_in;
94+
tf2::Transform tf_orig2target;
95+
tf2::Transform tf_map2target;
96+
97+
tf2::Stamped<tf2::Transform> transformStamped_temp;
98+
try {
99+
// Get the transform from camera to target
100+
geometry_msgs::TransformStamped tf_msg = tfBuffer->lookupTransform(frame_in, frame_target, ros::Time(0));
101+
// Convert to tf2
102+
tf2::fromMsg(tf_msg, transformStamped_temp);
103+
tf_orig2target.setBasis(transformStamped_temp.getBasis());
104+
tf_orig2target.setOrigin(transformStamped_temp.getOrigin());
105+
106+
} catch (tf2::TransformException &ex) {
107+
ROS_WARN("%s",ex.what());
108+
//ros::Duration(1.0).sleep();
109+
tf_orig2target.setIdentity();
110+
}
111+
112+
/*
113+
// Print debug info
114+
double roll, pitch, yaw;
115+
// Print debug map2orig
116+
tf2::Matrix3x3(tf_map2orig.getRotation()).getRPY(roll, pitch, yaw);
117+
ROS_INFO("Static transform Map to Orig [%s -> %s]",
118+
map_frame_id_param_.c_str(), frame_in.c_str());
119+
ROS_INFO(" * Translation: {%.3f,%.3f,%.3f}",
120+
tf_map2orig.getOrigin().x(), tf_map2orig.getOrigin().y(), tf_map2orig.getOrigin().z());
121+
ROS_INFO(" * Rotation: {%.3f,%.3f,%.3f}",
122+
RAD2DEG(roll), RAD2DEG(pitch), RAD2DEG(yaw));
123+
// Print debug tf_orig2target
124+
tf2::Matrix3x3(tf_orig2target.getRotation()).getRPY(roll, pitch, yaw);
125+
ROS_INFO("Static transform Orig to Target [%s -> %s]",
126+
frame_in.c_str(), frame_target.c_str());
127+
ROS_INFO(" * Translation: {%.3f,%.3f,%.3f}",
128+
tf_orig2target.getOrigin().x(), tf_orig2target.getOrigin().y(), tf_orig2target.getOrigin().z());
129+
ROS_INFO(" * Rotation: {%.3f,%.3f,%.3f}",
130+
RAD2DEG(roll), RAD2DEG(pitch), RAD2DEG(yaw));
131+
// Print debug map2target
132+
tf2::Matrix3x3(tf_map2target.getRotation()).getRPY(roll, pitch, yaw);
133+
ROS_INFO("Static transform Map to Target [%s -> %s]",
134+
map_frame_id_param_.c_str(), frame_target.c_str());
135+
ROS_INFO(" * Translation: {%.3f,%.3f,%.3f}",
136+
tf_map2target.getOrigin().x(), tf_map2target.getOrigin().y(), tf_map2target.getOrigin().z());
137+
ROS_INFO(" * Rotation: {%.3f,%.3f,%.3f}",
138+
RAD2DEG(roll), RAD2DEG(pitch), RAD2DEG(yaw));
139+
*/
140+
141+
// Transform from map to target
142+
tf_map2target = tf_map2orig * tf_orig2target;
143+
return tf_map2target;
144+
}
86145

87146
void Node::PublishPositionAsTransform (cv::Mat position) {
88147
// Get transform from map to camera frame
89148
tf2::Transform tf_transform = TransformFromMat(position);
90149

150+
// Make transform from camera frame to target frame
151+
tf2::Transform tf_map2target = TransformToTarget(tf_transform, camera_frame_id_param_, target_frame_id_param_);
152+
91153
// Make message
92-
tf2::Stamped<tf2::Transform> tf_transform_stamped;
93-
tf_transform_stamped = tf2::Stamped<tf2::Transform>(tf_transform, current_frame_time_, map_frame_id_param_);
94-
geometry_msgs::TransformStamped msg = tf2::toMsg(tf_transform_stamped);
95-
msg.child_frame_id = camera_frame_id_param_;
154+
tf2::Stamped<tf2::Transform> tf_map2target_stamped;
155+
tf_map2target_stamped = tf2::Stamped<tf2::Transform>(tf_map2target, current_frame_time_, map_frame_id_param_);
156+
geometry_msgs::TransformStamped msg = tf2::toMsg(tf_map2target_stamped);
157+
msg.child_frame_id = target_frame_id_param_;
96158
// Broadcast tf
97159
static tf2_ros::TransformBroadcaster tf_broadcaster;
98160
tf_broadcaster.sendTransform(msg);
99161
}
100162

101163
void Node::PublishPositionAsPoseStamped (cv::Mat position) {
102164
tf2::Transform tf_position = TransformFromMat(position);
165+
166+
// Make transform from camera frame to target frame
167+
tf2::Transform tf_position_target = TransformToTarget(tf_position, camera_frame_id_param_, target_frame_id_param_);
103168

104169
// Make message
105-
tf2::Stamped<tf2::Transform> tf_position_stamped;
106-
tf_position_stamped = tf2::Stamped<tf2::Transform>(tf_position, current_frame_time_, map_frame_id_param_);
170+
tf2::Stamped<tf2::Transform> tf_position_target_stamped;
171+
tf_position_target_stamped = tf2::Stamped<tf2::Transform>(tf_position_target, current_frame_time_, map_frame_id_param_);
107172
geometry_msgs::PoseStamped pose_msg;
108-
tf2::toMsg(tf_position_stamped, pose_msg);
173+
tf2::toMsg(tf_position_target_stamped, pose_msg);
109174
pose_publisher_.publish(pose_msg);
110175
}
111176

0 commit comments

Comments
 (0)