ros2_control - rolling
Loading...
Searching...
No Matches
hardware_component.hpp
1// Copyright 2020 - 2021 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 HARDWARE_INTERFACE__HARDWARE_COMPONENT_HPP_
16#define HARDWARE_INTERFACE__HARDWARE_COMPONENT_HPP_
17
18#include <memory>
19#include <string>
20#include <vector>
21
22#include "hardware_interface/handle.hpp"
23#include "hardware_interface/hardware_component_interface.hpp"
24#include "hardware_interface/hardware_info.hpp"
25#include "hardware_interface/types/hardware_interface_return_values.hpp"
26#include "hardware_interface/types/statistics_types.hpp"
27#include "rclcpp/duration.hpp"
28#include "rclcpp/logger.hpp"
29#include "rclcpp/node_interfaces/node_clock_interface.hpp"
30#include "rclcpp/time.hpp"
31#include "rclcpp_lifecycle/state.hpp"
32
33namespace hardware_interface
34{
35class HardwareComponentInterface;
36
38{
39public:
40 HardwareComponent() = default;
41
42 explicit HardwareComponent(std::unique_ptr<HardwareComponentInterface> impl);
43
44 explicit HardwareComponent(HardwareComponent && other) noexcept;
45
46 ~HardwareComponent() = default;
47
48 HardwareComponent(const HardwareComponent & other) = delete;
49
50 HardwareComponent & operator=(const HardwareComponent & other) = delete;
51
52 HardwareComponent & operator=(HardwareComponent && other) = delete;
53
54 const rclcpp_lifecycle::State & initialize(
56
57 const rclcpp_lifecycle::State & configure();
58
59 const rclcpp_lifecycle::State & cleanup();
60
61 const rclcpp_lifecycle::State & shutdown();
62
63 const rclcpp_lifecycle::State & activate();
64
65 const rclcpp_lifecycle::State & deactivate();
66
67 const rclcpp_lifecycle::State & error();
68
69 std::vector<StateInterface::ConstSharedPtr> export_state_interfaces();
70
71 std::vector<CommandInterface::SharedPtr> export_command_interfaces();
72
73 return_type prepare_command_mode_switch(
74 const std::vector<std::string> & start_interfaces,
75 const std::vector<std::string> & stop_interfaces);
76
77 return_type perform_command_mode_switch(
78 const std::vector<std::string> & start_interfaces,
79 const std::vector<std::string> & stop_interfaces);
80
81 const std::string & get_name() const;
82
83 const std::string & get_group_name() const;
84
85 const rclcpp_lifecycle::State & get_lifecycle_state() const;
86
87 const rclcpp::Time & get_last_read_time() const;
88
89 const rclcpp::Time & get_last_write_time() const;
90
91 const HardwareComponentStatisticsCollector & get_read_statistics() const;
92
93 const HardwareComponentStatisticsCollector & get_write_statistics() const;
94
95 return_type read(const rclcpp::Time & time, const rclcpp::Duration & period);
96
97 return_type write(const rclcpp::Time & time, const rclcpp::Duration & period);
98
99 std::recursive_mutex & get_mutex();
100
101private:
102 std::unique_ptr<HardwareComponentInterface> impl_;
103 mutable std::recursive_mutex component_mutex_;
104 // Last read cycle time
105 rclcpp::Time last_read_cycle_time_;
106 // Last write cycle time
107 rclcpp::Time last_write_cycle_time_;
108 // Component statistics
109 HardwareComponentStatisticsCollector read_statistics_;
110 HardwareComponentStatisticsCollector write_statistics_;
111};
112
113} // namespace hardware_interface
114#endif // HARDWARE_INTERFACE__HARDWARE_COMPONENT_HPP_
Definition hardware_component.hpp:38
Definition actuator.hpp:22
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_params.hpp:33