-
Notifications
You must be signed in to change notification settings - Fork 262
Adding demo for Example 3 : Industrial Robots with integrated sensor #68
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 7 commits
0866c42
b22dd4d
ba8699e
63294eb
6310687
a6f2052
76d8a4f
5d83ae1
be0f534
0964132
edf9b04
d56c698
781f388
10a96cd
6c5b485
7e53311
fbb840c
263377c
21599cd
60cd85a
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,77 @@ | ||
| // Copyright 2021 ros2_control Development Team | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
|
|
||
| #ifndef ROS2_CONTROL_DEMO_HARDWARE__RRBOT_SYSTEM_WITH_SENSOR_HPP_ | ||
| #define ROS2_CONTROL_DEMO_HARDWARE__RRBOT_SYSTEM_WITH_SENSOR_HPP_ | ||
|
|
||
| #include <memory> | ||
| #include <string> | ||
| #include <vector> | ||
|
|
||
|
|
||
| #include "hardware_interface/base_interface.hpp" | ||
| #include "hardware_interface/system_interface.hpp" | ||
| #include "hardware_interface/handle.hpp" | ||
| #include "hardware_interface/hardware_info.hpp" | ||
| #include "hardware_interface/types/hardware_interface_return_values.hpp" | ||
| #include "hardware_interface/types/hardware_interface_status_values.hpp" | ||
| #include "rclcpp/macros.hpp" | ||
| #include "ros2_control_demo_hardware/visibility_control.h" | ||
|
|
||
| using hardware_interface::return_type; | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @bmagyar, @Karsten1987, @v-lopez Should we remove "using" from the official examples?
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I agree (and saw you did on the PR), specially with such a generic name as return_type.
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @bailaC can you also remove this using? And then adapt the files accordingly?
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. These names are long and mostly meaningless. The motivation was to keep them as short as possible, especially in compilation units that are very likely to be leaf nodes such as these system plugins. I personally prefer short, readable code to adhering to semi-enterprise, cover-all-cases style guides. That is only my opinion though, feel free to change it if you see fit. |
||
|
|
||
| namespace ros2_control_demo_hardware | ||
| { | ||
| class RRBotSystemWithSensorHardware : public | ||
| hardware_interface::BaseInterface<hardware_interface::SystemInterface> | ||
| { | ||
| public: | ||
| RCLCPP_SHARED_PTR_DEFINITIONS(RRBotSystemWithSensorHardware); | ||
bailaC marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| return_type configure(const hardware_interface::HardwareInfo & info) override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| std::vector<hardware_interface::StateInterface> export_state_interfaces() override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| std::vector<hardware_interface::CommandInterface> export_command_interfaces() override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| return_type start() override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| return_type stop() override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| return_type read() override; | ||
|
|
||
| ROS2_CONTROL_DEMO_HARDWARE_PUBLIC | ||
| return_type write() override; | ||
|
|
||
| private: | ||
| // Parameters for the RRBot simulation | ||
| double hw_start_sec_; | ||
| double hw_stop_sec_; | ||
|
|
||
| // Store the command for the simulated robot | ||
| std::vector<double> hw_joint_commands_; | ||
| std::vector<double> hw_joint_states_; | ||
| std::vector<double> hw_sensor_states_; | ||
| }; | ||
|
|
||
| } // namespace ros2_control_demo_hardware | ||
|
|
||
| #endif // ROS2_CONTROL_DEMO_HARDWARE__RRBOT_SYSTEM_WITH_SENSOR_HPP_ | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,240 @@ | ||
| // Copyright 2021 ros2_control Development Team | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #include "ros2_control_demo_hardware/rrbot_system_with_sensor.hpp" | ||
|
|
||
| #include <chrono> | ||
| #include <cmath> | ||
| #include <limits> | ||
| #include <memory> | ||
| #include <vector> | ||
|
|
||
| #include "hardware_interface/types/hardware_interface_type_values.hpp" | ||
| #include "rclcpp/rclcpp.hpp" | ||
|
|
||
| namespace ros2_control_demo_hardware | ||
| { | ||
|
|
||
| return_type RRBotSystemWithSensorHardware::configure( | ||
| const hardware_interface::HardwareInfo & info) | ||
| { | ||
| if (configure_default(info) != return_type::OK) { | ||
| return return_type::ERROR; | ||
| } | ||
|
|
||
| hw_start_sec_ = stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); | ||
| hw_stop_sec_ = stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); | ||
| hw_joint_states_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN()); | ||
| hw_joint_commands_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN()); | ||
| hw_sensor_states_.resize( | ||
| info_.sensors[0].state_interfaces.size(), | ||
| std::numeric_limits<double>::quiet_NaN()); | ||
|
|
||
| for (const hardware_interface::ComponentInfo & joint : info_.joints) { | ||
| // RRBotSystemWithSensor has exactly one state and command interface on each joint | ||
| if (joint.command_interfaces.size() != 1) { | ||
| RCLCPP_FATAL( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
bailaC marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| "Joint '%s' has %d command interfaces found. 1 expected.", | ||
| joint.name.c_str(), joint.command_interfaces.size()); | ||
| return return_type::ERROR; | ||
| } | ||
|
|
||
| if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION) { | ||
| RCLCPP_FATAL( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Joint '%s' have %s command interfaces found. '%s' expected.", | ||
| joint.name.c_str(), joint.command_interfaces[0].name.c_str(), | ||
| hardware_interface::HW_IF_POSITION); | ||
| return return_type::ERROR; | ||
| } | ||
|
|
||
| if (joint.state_interfaces.size() != 1) { | ||
| RCLCPP_FATAL( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Joint '%s' has %d state interface. 1 expected.", | ||
| joint.name.c_str(), joint.state_interfaces.size()); | ||
| return return_type::ERROR; | ||
| } | ||
|
|
||
| if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) { | ||
| RCLCPP_FATAL( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Joint '%s' have %s state interface. '%s' expected.", | ||
| joint.name.c_str(), joint.state_interfaces[0].name.c_str(), | ||
| hardware_interface::HW_IF_POSITION); | ||
| return return_type::ERROR; | ||
| } | ||
| } | ||
|
|
||
| // RRBotSystemWithSensor has six state interfaces for one sensor | ||
| if (info_.sensors[0].state_interfaces.size() != 2) { | ||
| RCLCPP_FATAL( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Sensor '%s' has %d state interface. 2 expected.", | ||
| info_.sensors[0].name.c_str(), info_.sensors[0].state_interfaces.size()); | ||
| return return_type::ERROR; | ||
| } | ||
|
|
||
| status_ = hardware_interface::status::CONFIGURED; | ||
| return return_type::OK; | ||
| } | ||
|
|
||
| std::vector<hardware_interface::StateInterface> | ||
| RRBotSystemWithSensorHardware::export_state_interfaces() | ||
| { | ||
| std::vector<hardware_interface::StateInterface> state_interfaces; | ||
| for (uint i = 0; i < info_.joints.size(); i++) { | ||
| state_interfaces.emplace_back( | ||
| hardware_interface::StateInterface( | ||
| info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_joint_states_[i])); | ||
| } | ||
|
|
||
| // export sensor state interface | ||
| for (uint i = 0; i < info_.sensors[0].state_interfaces.size(); i++) { | ||
| state_interfaces.emplace_back( | ||
| hardware_interface::StateInterface( | ||
| info_.sensors[0].name, info_.sensors[0].state_interfaces[i].name, &hw_sensor_states_[i])); | ||
| } | ||
|
|
||
| return state_interfaces; | ||
| } | ||
|
|
||
| std::vector<hardware_interface::CommandInterface> | ||
| RRBotSystemWithSensorHardware::export_command_interfaces() | ||
| { | ||
| std::vector<hardware_interface::CommandInterface> command_interfaces; | ||
| for (uint i = 0; i < info_.joints.size(); i++) { | ||
| command_interfaces.emplace_back( | ||
| hardware_interface::CommandInterface( | ||
| info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_joint_commands_[i])); | ||
| } | ||
|
|
||
| return command_interfaces; | ||
| } | ||
|
|
||
| return_type RRBotSystemWithSensorHardware::start() | ||
| { | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Starting ...please wait..."); | ||
|
|
||
| for (int i = 0; i <= hw_start_sec_; i++) { | ||
| rclcpp::sleep_for(std::chrono::seconds(1)); | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "%.1f seconds left...", hw_start_sec_ - i); | ||
| } | ||
|
|
||
| // set some default values for joints | ||
| for (uint i = 0; i < hw_joint_states_.size(); i++) { | ||
| if (std::isnan(hw_joint_states_[i])) { | ||
| hw_joint_states_[i] = 0; | ||
| hw_joint_commands_[i] = 0; | ||
| } | ||
| } | ||
|
|
||
| // set default value for sensor | ||
| if (std::isnan(hw_sensor_states_[0])) { | ||
| hw_sensor_states_[0] = 0; | ||
| } | ||
|
|
||
| status_ = hardware_interface::status::STARTED; | ||
|
|
||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "System Sucessfully started!"); | ||
|
|
||
| return return_type::OK; | ||
| } | ||
|
|
||
| return_type RRBotSystemWithSensorHardware::stop() | ||
| { | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Stopping ...please wait..."); | ||
|
|
||
| for (int i = 0; i <= hw_stop_sec_; i++) { | ||
| rclcpp::sleep_for(std::chrono::seconds(1)); | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "%.1f seconds left...", hw_stop_sec_ - i); | ||
| } | ||
|
|
||
| status_ = hardware_interface::status::STOPPED; | ||
|
|
||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "System sucessfully stopped!"); | ||
|
|
||
| return return_type::OK; | ||
| } | ||
|
|
||
| hardware_interface::return_type RRBotSystemWithSensorHardware::read() | ||
| { | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Reading...please wait..."); | ||
|
|
||
| for (uint i = 0; i < hw_joint_states_.size(); i++) { | ||
| // Simulate RRBot's movement | ||
| hw_joint_states_[i] = hw_joint_commands_[i] + | ||
| (hw_joint_states_[i] - hw_joint_commands_[i]) / 2.0; | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Got state %.5f for joint %d!", hw_joint_states_[i], i); | ||
| } | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Joints sucessfully read!"); | ||
|
|
||
| // Simulate RRBot's sensor data | ||
| hw_sensor_states_[0] = 1.1; | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Got state %.5f for sensor 0!", hw_sensor_states_[0]); | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Sensors sucessfully read!"); | ||
|
|
||
| return return_type::OK; | ||
| } | ||
|
|
||
| hardware_interface::return_type ros2_control_demo_hardware::RRBotSystemWithSensorHardware::write() | ||
| { | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Writing...please wait..."); | ||
|
|
||
| for (uint i = 0; i < hw_joint_commands_.size(); i++) { | ||
| // Simulate sending commands to the hardware | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Got command %.5f for joint %d!", hw_joint_commands_[i], i); | ||
| } | ||
| RCLCPP_INFO( | ||
| rclcpp::get_logger("RRBotSystemWithSensorHardware"), | ||
| "Joints sucessfully written!"); | ||
|
|
||
| return return_type::OK; | ||
| } | ||
|
|
||
| } // namespace ros2_control_demo_hardware | ||
|
|
||
| #include "pluginlib/class_list_macros.hpp" | ||
|
|
||
| PLUGINLIB_EXPORT_CLASS( | ||
| ros2_control_demo_hardware::RRBotSystemWithSensorHardware, | ||
| hardware_interface::SystemInterface | ||
| ) | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,29 @@ | ||
| controller_manager: | ||
| ros__parameters: | ||
| update_rate: 2 # Hz | ||
|
|
||
| forward_command_controller_position: | ||
| type: forward_command_controller/ForwardCommandController | ||
|
|
||
| joint_state_controller: | ||
| type: joint_state_controller/JointStateController | ||
|
|
||
| ur_controllers: | ||
| type: ur_controllers/ForceTorqueStateController | ||
|
|
||
| forward_command_controller_position: | ||
| ros__parameters: | ||
| joints: | ||
| - joint1 | ||
| - joint2 | ||
| interface_name: position | ||
|
|
||
| ur_controllers: | ||
| ros__parameters: | ||
| sensor_name: tcp_fts_sensor | ||
| state_interface_names: | ||
| - fx | ||
| - tz | ||
| frame_id: rrbot_tcp | ||
| lower_limits: -100 | ||
| upper_limits: 100 |
Uh oh!
There was an error while loading. Please reload this page.