Program Listing for File robot_utils.hpp
↰ Return to documentation for file (include/nav2_util/robot_utils.hpp
)
// 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.
#ifndef NAV2_UTIL__ROBOT_UTILS_HPP_
#define NAV2_UTIL__ROBOT_UTILS_HPP_
#include <string>
#include <memory>
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2/time.h"
#include "tf2/transform_datatypes.h"
#include "tf2_ros/buffer.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "rclcpp/rclcpp.hpp"
namespace nav2_util
{
bool getCurrentPose(
geometry_msgs::msg::PoseStamped & global_pose,
tf2_ros::Buffer & tf_buffer, const std::string global_frame = "map",
const std::string robot_frame = "base_link", const double transform_timeout = 0.1,
const rclcpp::Time stamp = rclcpp::Time());
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 = 0.1);
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);
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);
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,
geometry_msgs::msg::TransformStamped & transform_msg);
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,
geometry_msgs::msg::TransformStamped & transform_msg);
[[nodiscard]] bool validateTwist(const geometry_msgs::msg::Twist & msg);
[[nodiscard]] bool validateTwist(const geometry_msgs::msg::TwistStamped & msg);
} // end namespace nav2_util
#endif // NAV2_UTIL__ROBOT_UTILS_HPP_