ros2_control - iron
Loading...
Searching...
No Matches
joint_state_topic_hardware_interface.hpp
1// Copyright 2025 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/* Author: Jafar Abdi */
16
17#pragma once
18
19// C++
20#include <memory>
21#include <string>
22
23// ROS
24#include <hardware_interface/system_interface.hpp>
25#include <hardware_interface/types/hardware_component_interface_params.hpp>
26#include <rclcpp/node.hpp>
27#include <rclcpp/publisher.hpp>
28#include <rclcpp/subscription.hpp>
29
30#include <sensor_msgs/msg/joint_state.hpp>
31
32namespace joint_state_topic_hardware_interface
33{
34using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
35
37{
38public:
39 CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams& params) override;
40
41 std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
42
43 std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
44
45 hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
46
47 hardware_interface::return_type write(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) override;
48
49private:
50 rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr topic_based_joint_states_subscriber_;
51 rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr topic_based_joint_commands_publisher_;
52 sensor_msgs::msg::JointState latest_joint_state_;
53 bool sum_wrapped_joint_states_{ false };
54
56 std::array<std::string, 4> standard_interfaces_ = {
59 };
60
61 struct MimicJoint
62 {
63 std::size_t joint_index;
64 std::size_t mimicked_joint_index;
65 double multiplier = 1.0;
66 };
67 std::vector<MimicJoint> mimic_joints_;
68
70 std::vector<std::vector<double>> joint_commands_;
71 std::vector<std::vector<double>> joint_states_;
72
73 // If the difference between the current joint state and joint command is less than this value,
74 // the joint command will not be published.
75 double trigger_joint_command_threshold_ = 1e-5;
76
77 template <typename HandleType>
78 bool getInterface(const std::string& name, const std::string& interface_name, const size_t vector_index,
79 std::vector<std::vector<double>>& values, std::vector<HandleType>& interfaces);
80};
81
82} // namespace joint_state_topic_hardware_interface
Definition system_interface.hpp:73
Definition joint_state_topic_hardware_interface.hpp:37
hardware_interface::return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition joint_state_topic_hardware_interface.cpp:244
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition joint_state_topic_hardware_interface.cpp:187
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition joint_state_topic_hardware_interface.cpp:146
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition joint_state_topic_hardware_interface.cpp:167
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21