ros2_control - humble
Loading...
Searching...
No Matches
r6bot_hardware.hpp
1// Copyright 2023 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#ifndef ROS2_CONTROL_DEMO_EXAMPLE_7__R6BOT_HARDWARE_HPP_
16#define ROS2_CONTROL_DEMO_EXAMPLE_7__R6BOT_HARDWARE_HPP_
17
18#include "string"
19#include "unordered_map"
20#include "vector"
21
22#include "hardware_interface/handle.hpp"
23#include "hardware_interface/hardware_info.hpp"
24#include "hardware_interface/system_interface.hpp"
25#include "hardware_interface/types/hardware_interface_return_values.hpp"
26#include "hardware_interface/types/hardware_interface_type_values.hpp"
27
28using hardware_interface::return_type;
29
30namespace ros2_control_demo_example_7
31{
32using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
33
34class HARDWARE_INTERFACE_PUBLIC RobotSystem : public hardware_interface::SystemInterface
35{
36public:
37 CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;
38
39 std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
40
41 std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
42
43 return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;
44
45 return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override;
46
47protected:
49 std::vector<double> joint_position_command_;
50 std::vector<double> joint_velocities_command_;
51 std::vector<double> joint_position_;
52 std::vector<double> joint_velocities_;
53 std::vector<double> ft_states_;
54 std::vector<double> ft_command_;
55
56 std::unordered_map<std::string, std::vector<std::string>> joint_interfaces = {
57 {"position", {}}, {"velocity", {}}};
58};
59
60} // namespace ros2_control_demo_example_7
61
62#endif // ROS2_CONTROL_DEMO_EXAMPLE_7__R6BOT_HARDWARE_HPP_
Definition system_interface.hpp:73
Definition r6bot_hardware.hpp:35
std::vector< double > joint_position_command_
The size of this vector is (standard_interfaces_.size() x nr_joints)
Definition r6bot_hardware.hpp:49
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:106