-
Notifications
You must be signed in to change notification settings - Fork 1.4k
/
Copy pathrobot_utils.cpp
145 lines (129 loc) · 4.68 KB
/
robot_utils.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2019 Steven Macenski
// Copyright (c) 2019 Samsung Research America
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <string>
#include <memory>
#include "tf2/convert.h"
#include "nav2_util/robot_utils.hpp"
#include "rclcpp/logger.hpp"
namespace nav2_util
{
bool getCurrentPose(
geometry_msgs::msg::PoseStamped & global_pose,
tf2_ros::Buffer & tf_buffer, const std::string global_frame,
const std::string robot_frame, const double transform_timeout,
const rclcpp::Time stamp)
{
tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
global_pose.header.frame_id = robot_frame;
global_pose.header.stamp = stamp;
return transformPoseInTargetFrame(
global_pose, global_pose, tf_buffer, global_frame, transform_timeout);
}
bool transformPoseInTargetFrame(
const geometry_msgs::msg::PoseStamped & input_pose,
geometry_msgs::msg::PoseStamped & transformed_pose,
tf2_ros::Buffer & tf_buffer, const std::string target_frame,
const double transform_timeout)
{
static rclcpp::Logger logger = rclcpp::get_logger("transformPoseInTargetFrame");
try {
transformed_pose = tf_buffer.transform(
input_pose, target_frame,
tf2::durationFromSec(transform_timeout));
return true;
} catch (tf2::LookupException & ex) {
RCLCPP_ERROR(
logger,
"No Transform available Error looking up target frame: %s\n", ex.what());
} catch (tf2::ConnectivityException & ex) {
RCLCPP_ERROR(
logger,
"Connectivity Error looking up target frame: %s\n", ex.what());
} catch (tf2::ExtrapolationException & ex) {
RCLCPP_ERROR(
logger,
"Extrapolation Error looking up target frame: %s\n", ex.what());
} catch (tf2::TimeoutException & ex) {
RCLCPP_ERROR(
logger,
"Transform timeout with tolerance: %.4f", transform_timeout);
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(
logger, "Failed to transform from %s to %s",
input_pose.header.frame_id.c_str(), target_frame.c_str());
}
return false;
}
bool getTransform(
const std::string & source_frame_id,
const std::string & target_frame_id,
const tf2::Duration & transform_tolerance,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
tf2::Transform & tf2_transform)
{
geometry_msgs::msg::TransformStamped transform;
tf2_transform.setIdentity(); // initialize by identical transform
if (source_frame_id == target_frame_id) {
// We are already in required frame
return true;
}
try {
// Obtaining the transform to get data from source to target frame
transform = tf_buffer->lookupTransform(
target_frame_id, source_frame_id,
tf2::TimePointZero, transform_tolerance);
} catch (tf2::TransformException & e) {
RCLCPP_ERROR(
rclcpp::get_logger("getTransform"),
"Failed to get \"%s\"->\"%s\" frame transform: %s",
source_frame_id.c_str(), target_frame_id.c_str(), e.what());
return false;
}
// Convert TransformStamped to TF2 transform
tf2::fromMsg(transform.transform, tf2_transform);
return true;
}
bool getTransform(
const std::string & source_frame_id,
const rclcpp::Time & source_time,
const std::string & target_frame_id,
const rclcpp::Time & target_time,
const std::string & fixed_frame_id,
const tf2::Duration & transform_tolerance,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
tf2::Transform & tf2_transform)
{
geometry_msgs::msg::TransformStamped transform;
tf2_transform.setIdentity(); // initialize by identical transform
try {
// Obtaining the transform to get data from source to target frame.
// This also considers the time shift between source and target.
transform = tf_buffer->lookupTransform(
target_frame_id, target_time,
source_frame_id, source_time,
fixed_frame_id, transform_tolerance);
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(
rclcpp::get_logger("getTransform"),
"Failed to get \"%s\"->\"%s\" frame transform: %s",
source_frame_id.c_str(), target_frame_id.c_str(), ex.what());
return false;
}
// Convert TransformStamped to TF2 transform
tf2::fromMsg(transform.transform, tf2_transform);
return true;
}
} // end namespace nav2_util