Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
robot_utils.hpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2019 Steven Macenski
3 // Copyright (c) 2019 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #ifndef NAV2_UTIL__ROBOT_UTILS_HPP_
18 #define NAV2_UTIL__ROBOT_UTILS_HPP_
19 
20 #include <string>
21 #include <memory>
22 
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "geometry_msgs/msg/twist.hpp"
25 #include "tf2/time.h"
26 #include "tf2_ros/buffer.h"
27 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
28 #include "rclcpp/rclcpp.hpp"
29 
30 namespace nav2_util
31 {
41 bool getCurrentPose(
42  geometry_msgs::msg::PoseStamped & global_pose,
43  tf2_ros::Buffer & tf_buffer, const std::string global_frame = "map",
44  const std::string robot_frame = "base_link", const double transform_timeout = 0.1,
45  const rclcpp::Time stamp = rclcpp::Time());
46 
56 bool transformPoseInTargetFrame(
57  const geometry_msgs::msg::PoseStamped & input_pose,
58  geometry_msgs::msg::PoseStamped & transformed_pose,
59  tf2_ros::Buffer & tf_buffer, const std::string target_frame,
60  const double transform_timeout = 0.1);
61 
83 bool getTransform(
84  const std::string & source_frame_id,
85  const std::string & target_frame_id,
86  const tf2::Duration & transform_tolerance,
87  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
88  tf2::Transform & tf2_transform);
89 
103 bool getTransform(
104  const std::string & source_frame_id,
105  const rclcpp::Time & source_time,
106  const std::string & target_frame_id,
107  const rclcpp::Time & target_time,
108  const std::string & fixed_frame_id,
109  const tf2::Duration & transform_tolerance,
110  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
111  tf2::Transform & tf2_transform);
112 
118 bool validateTwist(const geometry_msgs::msg::Twist & msg);
119 
120 } // end namespace nav2_util
121 
122 #endif // NAV2_UTIL__ROBOT_UTILS_HPP_