staubli_driver_ros2 main
ROS2 control driver for Staubli robots
Loading...
Searching...
No Matches
staubli_hardware_interface.hpp
Go to the documentation of this file.
1// Copyright 2025 ICUBE Laboratory, University of Strasbourg
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: Thibault Poignonec (thibault.poignonec@gmail.fr)
16
17#ifndef STAUBLI_ROBOT_DRIVER__STAUBLI_HARDWARE_INTERFACE_HPP_
18#define STAUBLI_ROBOT_DRIVER__STAUBLI_HARDWARE_INTERFACE_HPP_
19
20// C++
21#include <memory>
22#include <string>
23#include <vector>
24
25// ROS2
26#include "rclcpp_lifecycle/state.hpp"
27
28// ROS2 Control
29#include "hardware_interface/hardware_info.hpp"
30#include "hardware_interface/system_interface.hpp"
31#include "hardware_interface/types/hardware_component_interface_params.hpp"
32
33// Staubli Robot Driver
37
38namespace staubli_robot_driver {
39
40class StaubliHardwareInterface : public hardware_interface::SystemInterface
41{
42public:
45
46 hardware_interface::CallbackReturn
47 on_init(const hardware_interface::HardwareComponentInterfaceParams & params) override;
48
49 hardware_interface::CallbackReturn
50 on_configure(const rclcpp_lifecycle::State& previous_state) final;
51
52 hardware_interface::CallbackReturn
53 on_activate(const rclcpp_lifecycle::State& previous_state) final;
54
55 hardware_interface::CallbackReturn
56 on_cleanup(const rclcpp_lifecycle::State& previous_state) final;
57
58 hardware_interface::CallbackReturn
59 on_shutdown(const rclcpp_lifecycle::State& previous_state) final;
60
61 hardware_interface::CallbackReturn
62 on_error (const rclcpp_lifecycle::State& previous_state) final;
63
64 std::vector<hardware_interface::StateInterface> export_state_interfaces() final;
65
67
68 hardware_interface::return_type
70
71 hardware_interface::return_type
73
74 hardware_interface::return_type
77
78 hardware_interface::return_type
81
84 CommandType resolve_mode(const std::vector<std::string>& start_interfaces) const;
85
87 bool update_state(const RobotStateMessage& state_msg);
88
91 std::shared_ptr<RobotDriver> robot_driver_;
92
94 RobotStateMessage state_msg_;
95
97 CommandType current_control_mode_;
98
101 CommandType pending_mode_;
102
104 bool switch_prepared_;
105
106 struct SupervisionGpio {
107 double operation_mode;
108 double operation_mode_status;
109 double safety_status;
110 double control_sequence_delay;
111 // Bool values
112 double brakes_released;
113 double motion_possible;
114 double in_motion;
115 double in_error;
116 double estop_pressed;
117 double wait_for_ack;
118 };
119
120 // Copy of supervision GPIO for state interface
121 SupervisionGpio supervision_gpio_copy_;
122
123 // Joint state
124 size_t num_joints_;
125 std::vector<double> hw_joint_positions_;
126 std::vector<double> hw_joint_velocities_;
127 std::vector<double> hw_joint_efforts_;
128
129 // Joint commands
130 std::vector<double> hw_joint_position_commands_;
131 std::vector<double> hw_joint_velocity_commands_;
132
140 std::vector<double> hw_joint_acceleration_commands_;
141
142 // GPIO state
143 std::vector<double> hw_digital_inputs_;
144 std::vector<double> hw_analog_inputs_;
145 std::vector<double> hw_digital_outputs_;
146 std::vector<double> hw_analog_outputs_;
147
148 // GPIO command
149 std::vector<double> hw_digital_output_commands_;
150 std::vector<double> hw_analog_output_commands_;
151};
152
153} // namespace staubli_robot_driver
154
155#endif // STAUBLI_ROBOT_DRIVER__STAUBLI_HARDWARE_INTERFACE_HPP_
Bilateral real-time socket interface for pub/sub communication.
Definition real_time_socket_interface.hpp:39
Main interface for controlling Staubli robots.
Definition robot_driver.hpp:42
Robot state message.
Definition messages.hpp:62
Definition staubli_hardware_interface.hpp:41
hardware_interface::return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) final
std::vector< hardware_interface::StateInterface > export_state_interfaces() final
std::vector< hardware_interface::CommandInterface > export_command_interfaces() final
hardware_interface::return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) final
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) final
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) final
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &previous_state) final
hardware_interface::CallbackReturn on_error(const rclcpp_lifecycle::State &previous_state) final
hardware_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &previous_state) final
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params) override
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) final
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) final
Definition messages.hpp:23
CommandType
Command types.
Definition types.hpp:35