42#include <hardware_interface/internal/hardware_resource_manager.h>
43#include <tf2_ros/transform_listener.h>
44#include <tf2_ros/transform_broadcaster.h>
54 RobotStateHandle(std::string name, tf2_ros::Buffer* buffer) : name_(std::move(name)), buffer_(buffer)
57 throw hardware_interface::HardwareInterfaceException(
"Cannot create handle '" + name +
58 "'. Tf Buffer data pointer is null.");
61 geometry_msgs::TransformStamped
lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
62 const ros::Time& time)
64 return buffer_->lookupTransform(target_frame, source_frame, time);
67 bool setTransform(
const geometry_msgs::TransformStamped& transform,
const std::string& authority,
68 bool is_static =
false)
const
70 return buffer_->setTransform(transform, authority, is_static);
73 bool setTransform(
const std::vector<geometry_msgs::TransformStamped>& transforms,
const std::string& authority,
74 bool is_static =
false)
const
76 for (
const auto& transform : transforms)
77 buffer_->setTransform(transform, authority, is_static);
88 tf2_ros::Buffer* buffer_{};
92 :
public hardware_interface::HardwareResourceManager<RobotStateHandle, hardware_interface::DontClaimResources>
Definition robot_state_interface.h:51
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false) const
Definition robot_state_interface.h:67
RobotStateHandle()=default
bool setTransform(const std::vector< geometry_msgs::TransformStamped > &transforms, const std::string &authority, bool is_static=false) const
Definition robot_state_interface.h:73
RobotStateHandle(std::string name, tf2_ros::Buffer *buffer)
Definition robot_state_interface.h:54
std::string getName() const
Definition robot_state_interface.h:81
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time)
Definition robot_state_interface.h:61
Definition robot_state_interface.h:93
Definition actuator_extra_interface.h:44