@@ -7,110 +7,110 @@ namespace robotiq_hande_driver {
77
88RobotiqHandeHardwareInterface::RobotiqHandeHardwareInterface () {}
99
10- HWI::CallbackReturn RobotiqHandeHardwareInterface::on_init (
11- const HWI::HardwareInfo& info) {
12- if (HWI::SystemInterface::on_init (info) != CallbackReturn::SUCCESS) {
13- return HWI::CallbackReturn::ERROR;
14- }
10+ HWI::CallbackReturn RobotiqHandeHardwareInterface::on_init (const HWI::HardwareInfo& info) {
11+ if (HWI::SystemInterface::on_init (info) != CallbackReturn::SUCCESS) {
12+ return HWI::CallbackReturn::ERROR;
13+ }
1514
16- state_position_ = 0.025 ;
17- state_velocity_ = 0.0 ;
18- cmd_position_ = 0.025 ;
19- tty_port_ = info_.hardware_parameters [" tty" ];
15+ state_position_ = 0.025 ;
16+ state_velocity_ = 0.0 ;
17+ cmd_position_ = 0.025 ;
18+ tty_port_ = info_.hardware_parameters [" tty" ];
2019
21- logger_ = std::make_shared<rclcpp::Logger>(
22- rclcpp::get_logger (" controller_manager.resource_manager.hardware_"
23- " component.system.RobotiqHandeHardwareInterface" ));
20+ logger_ = std::make_shared<rclcpp::Logger>(
21+ rclcpp::get_logger (" controller_manager.resource_manager.hardware_"
22+ " component.system.RobotiqHandeHardwareInterface" ));
2423
25- // TODO(modbus integration): Set parameters for the modbus communication
24+ // TODO(modbus integration): Set parameters for the modbus communication
2625
27- RCLCPP_INFO (get_logger (), " Initialized ModbusRTU for %s" , tty_port_.c_str ());
28- return HWI::CallbackReturn::SUCCESS;
26+ RCLCPP_INFO (get_logger (), " Initialized ModbusRTU for %s" , tty_port_.c_str ());
27+ return HWI::CallbackReturn::SUCCESS;
2928}
3029
3130HWI::CallbackReturn RobotiqHandeHardwareInterface::on_configure (
3231 const rlccp_lc::State& /* previous_state*/ ) {
33- // TODO(modbus integration): Initialize the ModbusRTU communication session
34- RCLCPP_INFO (get_logger (), " configure()" );
35- return HWI::CallbackReturn::SUCCESS;
32+ // TODO(modbus integration): Initialize the ModbusRTU communication session
33+ RCLCPP_INFO (get_logger (), " configure()" );
34+ return HWI::CallbackReturn::SUCCESS;
3635}
3736
3837HWI::CallbackReturn RobotiqHandeHardwareInterface::on_cleanup (
3938 const rlccp_lc::State& /* previous_state*/ ) {
40- // TODO(modbus integration): Deinitalize the ModbusRTU session
41- RCLCPP_INFO (get_logger (), " cleanup()" );
42- return HWI::CallbackReturn::SUCCESS;
39+ // TODO(modbus integration): Deinitalize the ModbusRTU session
40+ RCLCPP_INFO (get_logger (), " cleanup()" );
41+ return HWI::CallbackReturn::SUCCESS;
4342}
4443
45- std::vector<HWI::StateInterface>
46- RobotiqHandeHardwareInterface::export_state_interfaces () {
47- std::vector<HWI::StateInterface> state_interfaces;
44+ std::vector<HWI::StateInterface> RobotiqHandeHardwareInterface::export_state_interfaces () {
45+ std::vector<HWI::StateInterface> state_interfaces;
4846
49- state_interfaces.emplace_back (hardware_interface::StateInterface (
50- info_.joints [LEFT_FINGER_JOINT_ID].name ,
51- hardware_interface::HW_IF_POSITION, &state_position_));
52- state_interfaces.emplace_back (hardware_interface::StateInterface (
53- info_.joints [LEFT_FINGER_JOINT_ID].name ,
54- hardware_interface::HW_IF_VELOCITY, &state_velocity_));
47+ state_interfaces.emplace_back (hardware_interface::StateInterface (
48+ info_.joints [LEFT_FINGER_JOINT_ID].name ,
49+ hardware_interface::HW_IF_POSITION,
50+ &state_position_));
51+ state_interfaces.emplace_back (hardware_interface::StateInterface (
52+ info_.joints [LEFT_FINGER_JOINT_ID].name ,
53+ hardware_interface::HW_IF_VELOCITY,
54+ &state_velocity_));
5555
56- RCLCPP_INFO (get_logger (), " export_state_interfaces()" );
57- return state_interfaces;
56+ RCLCPP_INFO (get_logger (), " export_state_interfaces()" );
57+ return state_interfaces;
5858}
5959
60- std::vector<HWI::CommandInterface>
61- RobotiqHandeHardwareInterface::export_command_interfaces () {
62- std::vector<hardware_interface::CommandInterface> command_interfaces;
60+ std::vector<HWI::CommandInterface> RobotiqHandeHardwareInterface::export_command_interfaces () {
61+ std::vector<hardware_interface::CommandInterface> command_interfaces;
6362
64- command_interfaces.emplace_back (hardware_interface::CommandInterface (
65- info_.joints [LEFT_FINGER_JOINT_ID].name ,
66- hardware_interface::HW_IF_POSITION, &cmd_position_));
63+ command_interfaces.emplace_back (hardware_interface::CommandInterface (
64+ info_.joints [LEFT_FINGER_JOINT_ID].name ,
65+ hardware_interface::HW_IF_POSITION,
66+ &cmd_position_));
6767
68- RCLCPP_INFO (get_logger (), " export_command_interfaces()" );
69- return command_interfaces;
68+ RCLCPP_INFO (get_logger (), " export_command_interfaces()" );
69+ return command_interfaces;
7070}
7171
7272HWI::CallbackReturn RobotiqHandeHardwareInterface::on_activate (
7373 const rlccp_lc::State& /* previous_state*/ ) {
74- // TODO(modbus integration): Power on the gripper (activation)
75- RCLCPP_INFO (get_logger (), " activate()" );
76- return HWI::CallbackReturn::SUCCESS;
74+ // TODO(modbus integration): Power on the gripper (activation)
75+ RCLCPP_INFO (get_logger (), " activate()" );
76+ return HWI::CallbackReturn::SUCCESS;
7777}
7878
7979HWI::CallbackReturn RobotiqHandeHardwareInterface::on_deactivate (
8080 const rlccp_lc::State& /* previous_state*/ ) {
81- // TODO(modbus integration): Deactiavte the gripper (set the reset flag)
82- RCLCPP_INFO (get_logger (), " deactivate()" );
83- return HWI::CallbackReturn::SUCCESS;
81+ // TODO(modbus integration): Deactiavte the gripper (set the reset flag)
82+ RCLCPP_INFO (get_logger (), " deactivate()" );
83+ return HWI::CallbackReturn::SUCCESS;
8484}
8585
8686HWI::CallbackReturn RobotiqHandeHardwareInterface::on_shutdown (
8787 const rlccp_lc::State& /* previous_state*/ ) {
88- // TODO(modbus integration): Deactivate the gripper, deinitalize the modbus
89- // RTU session,
90- RCLCPP_INFO (get_logger (), " shutdown()" );
91- return HWI::CallbackReturn::SUCCESS;
88+ // TODO(modbus integration): Deactivate the gripper, deinitalize the modbus
89+ // RTU session,
90+ RCLCPP_INFO (get_logger (), " shutdown()" );
91+ return HWI::CallbackReturn::SUCCESS;
9292}
9393
9494HWI::CallbackReturn RobotiqHandeHardwareInterface::on_error (
9595 const rlccp_lc::State& /* previous_state*/ ) {
96- // TODO(modbus integration): Placeholder for error handling
97- RCLCPP_INFO (get_logger (), " Handled error" );
98- return HWI::CallbackReturn::SUCCESS;
96+ // TODO(modbus integration): Placeholder for error handling
97+ RCLCPP_INFO (get_logger (), " Handled error" );
98+ return HWI::CallbackReturn::SUCCESS;
9999}
100100
101101HWI::return_type RobotiqHandeHardwareInterface::read (
102102 const rclcpp::Time& /* time*/ , const rclcpp::Duration& /* period*/ ) {
103- // TODO(modbus integration): data = driver_->receive_data();
104- return hardware_interface::return_type::OK;
103+ // TODO(modbus integration): data = driver_->receive_data();
104+ return hardware_interface::return_type::OK;
105105}
106106HWI::return_type RobotiqHandeHardwareInterface::write (
107107 const rclcpp::Time& /* time*/ , const rclcpp::Duration& /* period*/ ) {
108- // TODO(modbus integration): driver_->send_data(cmd_position_);
109- return hardware_interface::return_type::OK;
108+ // TODO(modbus integration): driver_->send_data(cmd_position_);
109+ return hardware_interface::return_type::OK;
110110}
111111
112112} // namespace robotiq_hande_driver
113113
114114#include " pluginlib/class_list_macros.hpp"
115- PLUGINLIB_EXPORT_CLASS (robotiq_hande_driver::RobotiqHandeHardwareInterface,
116- hardware_interface::SystemInterface)
115+ PLUGINLIB_EXPORT_CLASS (
116+ robotiq_hande_driver::RobotiqHandeHardwareInterface, hardware_interface::SystemInterface)
0 commit comments