|
1 | | -// Copyright 2020 ROS2-Control Development Team |
| 1 | +// Copyright 2020 ros2_control Development Team |
2 | 2 | // |
3 | 3 | // Licensed under the Apache License, Version 2.0 (the "License"); |
4 | 4 | // you may not use this file except in compliance with the License. |
@@ -37,53 +37,44 @@ return_type RRBotSystemPositionOnlyHardware::configure( |
37 | 37 | hw_stop_sec_ = stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); |
38 | 38 | hw_slowdown_ = stod(info_.hardware_parameters["example_param_hw_slowdown"]); |
39 | 39 | hw_states_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN()); |
40 | | - hw_commands_.resize(info_.joints.size()); |
41 | | - for (uint i = 0; i < info_.joints.size(); i++) { |
42 | | - hw_states_[i] = std::numeric_limits<double>::quiet_NaN(); |
43 | | - hw_commands_[i] = std::numeric_limits<double>::quiet_NaN(); |
44 | | - } |
| 40 | + hw_commands_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN()); |
| 41 | + |
| 42 | + for (const hardware_interface::ComponentInfo & joint : info_.joints) { |
| 43 | + // RRBotSystemPositionOnly has exactly one state and command interface on each joint |
| 44 | + if (joint.command_interfaces.size() != 1) { |
| 45 | + RCLCPP_FATAL( |
| 46 | + rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
| 47 | + "Joint '%s' has %d command interfaces found. 1 expected.", |
| 48 | + joint.name.c_str(), joint.command_interfaces.size()); |
| 49 | + return return_type::ERROR; |
| 50 | + } |
45 | 51 |
|
46 | | - // TODO(anyone): we should provide helpers for this checking somewhere |
47 | | - { |
48 | | - for (const hardware_interface::ComponentInfo & joint : info_.joints) { |
49 | | - // RRBotSystemPositionOnly has exactly one state and command interface on each joint |
50 | | - if (joint.command_interfaces.size() != 1) { |
51 | | - RCLCPP_FATAL( |
52 | | - rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
53 | | - "Joint '%s' has %d command interfaces found. 1 expected.", |
54 | | - joint.name.c_str(), joint.command_interfaces.size()); |
55 | | - return return_type::ERROR; |
56 | | - } |
57 | | - |
58 | | - if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { |
59 | | - RCLCPP_FATAL( |
60 | | - rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
61 | | - "Joint '%s' have %s command interfaces found. '%s' expected.", |
62 | | - joint.name.c_str(), joint.command_interfaces[0].name.c_str(), |
63 | | - hardware_interface::HW_IF_POSITION); |
64 | | - return return_type::ERROR; |
65 | | - } |
66 | | - |
67 | | - if (joint.state_interfaces.size() != 1) { |
68 | | - RCLCPP_FATAL( |
69 | | - rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
70 | | - "Joint '%s' has %d state interface. 1 expected.", |
71 | | - joint.name.c_str(), joint.state_interfaces.size()); |
72 | | - return return_type::ERROR; |
73 | | - } |
74 | | - |
75 | | - if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { |
76 | | - RCLCPP_FATAL( |
77 | | - rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
78 | | - "Joint '%s' have %s state interface. '%s' expected.", |
79 | | - joint.name.c_str(), joint.state_interfaces[0].name.c_str(), |
80 | | - hardware_interface::HW_IF_POSITION); |
81 | | - return return_type::ERROR; |
82 | | - } |
| 52 | + if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { |
| 53 | + RCLCPP_FATAL( |
| 54 | + rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
| 55 | + "Joint '%s' have %s command interfaces found. '%s' expected.", |
| 56 | + joint.name.c_str(), joint.command_interfaces[0].name.c_str(), |
| 57 | + hardware_interface::HW_IF_POSITION); |
| 58 | + return return_type::ERROR; |
83 | 59 | } |
84 | | - } |
85 | 60 |
|
86 | | - // TODO(all): ada support for different order of joints than "joint1", "joint2",... |
| 61 | + if (joint.state_interfaces.size() != 1) { |
| 62 | + RCLCPP_FATAL( |
| 63 | + rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
| 64 | + "Joint '%s' has %d state interface. 1 expected.", |
| 65 | + joint.name.c_str(), joint.state_interfaces.size()); |
| 66 | + return return_type::ERROR; |
| 67 | + } |
| 68 | + |
| 69 | + if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { |
| 70 | + RCLCPP_FATAL( |
| 71 | + rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), |
| 72 | + "Joint '%s' have %s state interface. '%s' expected.", |
| 73 | + joint.name.c_str(), joint.state_interfaces[0].name.c_str(), |
| 74 | + hardware_interface::HW_IF_POSITION); |
| 75 | + return return_type::ERROR; |
| 76 | + } |
| 77 | + } |
87 | 78 |
|
88 | 79 | status_ = hardware_interface::status::CONFIGURED; |
89 | 80 | return return_type::OK; |
@@ -213,5 +204,5 @@ hardware_interface::return_type ros2_control_demo_hardware::RRBotSystemPositionO |
213 | 204 |
|
214 | 205 | PLUGINLIB_EXPORT_CLASS( |
215 | 206 | ros2_control_demo_hardware::RRBotSystemPositionOnlyHardware, |
216 | | - hardware_interface::components::SystemInterface |
| 207 | + hardware_interface::SystemInterface |
217 | 208 | ) |
0 commit comments