robot_state_interface.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 1/3/21.
36 //
37 
38 #pragma once
39 
40 #include <utility>
41 
42 #include <hardware_interface/internal/hardware_resource_manager.h>
45 
47 
48 namespace rm_control
49 {
50 class RobotStateHandle
51 {
52 public:
53  RobotStateHandle() = default;
54  RobotStateHandle(std::string name, tf2_ros::Buffer* buffer) : name_(std::move(name)), buffer_(buffer)
55  {
56  if (!buffer)
57  throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + name +
58  "'. Tf Buffer data pointer is null.");
59  };
60 
61  geometry_msgs::TransformStamped lookupTransform(const std::string& target_frame, const std::string& source_frame,
62  const ros::Time& time)
63  {
64  return buffer_->lookupTransform(target_frame, source_frame, time);
65  }
66 
67  bool setTransform(const geometry_msgs::TransformStamped& transform, const std::string& authority,
68  bool is_static = false) const
69  {
70  return buffer_->setTransform(transform, authority, is_static);
71  }
72 
73  bool setTransform(const std::vector<geometry_msgs::TransformStamped>& transforms, const std::string& authority,
74  bool is_static = false) const
75  {
76  for (const auto& transform : transforms)
77  buffer_->setTransform(transform, authority, is_static);
78  return true;
79  }
80 
81  std::string getName() const
82  {
83  return name_;
84  }
85 
86 private:
87  std::string name_;
89 };
90 
91 class RobotStateInterface
92  : public hardware_interface::HardwareResourceManager<RobotStateHandle, hardware_interface::DontClaimResources>
93 {
94 };
95 } // namespace rm_control
rm_control::RobotStateHandle::lookupTransform
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time)
Definition: robot_state_interface.h:123
rm_control::RobotStateHandle::getName
std::string getName() const
Definition: robot_state_interface.h:143
tf2::BufferCore::setTransform
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
rm_control::RobotStateHandle::setTransform
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false) const
Definition: robot_state_interface.h:129
rm_control::RobotStateHandle::RobotStateHandle
RobotStateHandle()=default
transform_broadcaster.h
rm_control
Definition: actuator_extra_interface.h:43
tf2_ros::Buffer
transform_listener.h
ros::Time
std
rm_control::RobotStateHandle::name_
std::string name_
Definition: robot_state_interface.h:149
rm_control::RobotStateHandle::buffer_
tf2_ros::Buffer * buffer_
Definition: robot_state_interface.h:150
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
tf_rt_broadcaster.h


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01