Skip to content

Commit

Permalink
Deprecate fake components, long live mock components (#762)
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar committed Jul 5, 2022
1 parent 22da62d commit 1967cfa
Show file tree
Hide file tree
Showing 10 changed files with 242 additions and 122 deletions.
2 changes: 1 addition & 1 deletion doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -26,4 +26,4 @@ Concepts

Controller Manager <../controller_manager/doc/userdoc.rst>
Hardware Components <../hardware_interface/doc/hardware_components_userdoc.rst>
Fake Components <../hardware_interface/doc/fake_components_userdoc.rst>
Mock Components <../hardware_interface/doc/mock_components_userdoc.rst>
36 changes: 34 additions & 2 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,39 @@ ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS})
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME} PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL")

# Mock components
add_library(
mock_components
SHARED
src/mock_components/generic_system.cpp
)
target_include_directories(
mock_components
PUBLIC
include
)
target_link_libraries(
mock_components
${PROJECT_NAME}
)
ament_target_dependencies(
mock_components
pluginlib
rcpputils
)

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(mock_components PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL")

pluginlib_export_plugin_description_file(
${PROJECT_NAME} mock_components_plugin_description.xml)

# Fake components
add_library(
fake_components
SHARED
src/fake_components/generic_system.cpp
src/mock_components/generic_system.cpp
)
target_include_directories(
fake_components
Expand All @@ -60,13 +88,15 @@ ament_target_dependencies(
pluginlib
rcpputils
)

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(fake_components PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL")

pluginlib_export_plugin_description_file(
${PROJECT_NAME} fake_components_plugin_description.xml)


install(
DIRECTORY include/
DESTINATION include
Expand All @@ -75,6 +105,7 @@ install(
install(
TARGETS
fake_components
mock_components
${PROJECT_NAME}
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
Expand Down Expand Up @@ -134,7 +165,7 @@ if(BUILD_TESTING)
target_link_libraries(test_resource_manager ${PROJECT_NAME})
ament_target_dependencies(test_resource_manager ros2_control_test_assets)

ament_add_gmock(test_generic_system test/fake_components/test_generic_system.cpp)
ament_add_gmock(test_generic_system test/mock_components/test_generic_system.cpp)
target_include_directories(test_generic_system PRIVATE include)
target_link_libraries(test_generic_system ${PROJECT_NAME})
ament_target_dependencies(test_generic_system
Expand All @@ -148,6 +179,7 @@ ament_export_include_directories(
)
ament_export_libraries(
fake_components
mock_components
${PROJECT_NAME}
)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
.. _fake_components_userdoc:
.. _mock_components_userdoc:

Fake Components
Mock Components
----------------
Fake components are trivial "simulations" of the hardware components, i.e., System, Sensor, and Actuator.
Mock components are trivial "simulations" of the hardware components, i.e., System, Sensor, and Actuator.
They provide ideal behavior by mirroring commands to their states.
The corresponding hardware interface can be added instead of real hardware for offline testing of ros2_control framework.
The main advantage is that you can test all the "piping" inside the framework without having access to the hardware.
Expand Down
6 changes: 3 additions & 3 deletions hardware_interface/doc/writing_new_hardware_interface.rst
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ The following is a step-by-step guide to create source files, basic tests, and c
5. **Writing export definition for pluginlib**

1. Create the ``<my_hardware_interface_package>.xml`` file in the package and add a definition of the library and hardware interface's class which has to be visible for the pluginlib.
The easiest way to do that is to check definition for fake components in the `hardware_interface fake_components <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/fake_components_plugin_description.xml>`_ section.
The easiest way to do that is to check definition for mock components in the `hardware_interface mock_components <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/mock_components_plugin_description.xml>`_ section.

2. Usually, the plugin name is defined by the package (namespace) and the class name, e.g.,
``<my_hardware_interface_package>/<RobotHardwareInterfaceName>``.
Expand All @@ -88,7 +88,7 @@ The following is a step-by-step guide to create source files, basic tests, and c

1. Create the folder ``test`` in your package, if it does not exist already, and add a file named ``test_load_<robot_hardware_interface_name>.cpp``.

2. You can copy the ``load_generic_system_2dof`` content defined in the `test_generic_system.cpp <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/test/fake_components/test_generic_system.cpp#L402-L407>`_ package.
2. You can copy the ``load_generic_system_2dof`` content defined in the `test_generic_system.cpp <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/test/mock_components/test_generic_system.cpp#L402-L407>`_ package.

3. Change the name of the copied test and in the last line, where hardware interface type is specified put the name defined in ``<my_hardware_interface_package>.xml`` file, e.g., ``<my_hardware_interface_package>/<RobotHardwareInterfaceName>``.

Expand All @@ -113,7 +113,7 @@ The following is a step-by-step guide to create source files, basic tests, and c
7. In the test section add the following dependencies: ``ament_cmake_gmock``, ``hardware_interface``.

8. Add compile definitions for the tests using the ``ament_add_gmock`` directive.
For details, see how it is done for fake hardware in the `ros2_control <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/CMakeLists.txt>`_ package.
For details, see how it is done for mock hardware in the `ros2_control <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/CMakeLists.txt>`_ package.

9. (optional) Add your hardware interface`s library into ``ament_export_libraries`` before ``ament_package()``.

Expand Down
98 changes: 3 additions & 95 deletions hardware_interface/include/fake_components/generic_system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,105 +17,13 @@
#ifndef FAKE_COMPONENTS__GENERIC_SYSTEM_HPP_
#define FAKE_COMPONENTS__GENERIC_SYSTEM_HPP_

#include <string>
#include <vector>

#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"

using hardware_interface::return_type;
#include "hardware_interface/mock_components/generic_system.hpp"

namespace fake_components
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class HARDWARE_INTERFACE_PUBLIC GenericSystem : public hardware_interface::SystemInterface
{
public:
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;

std::vector<hardware_interface::StateInterface> export_state_interfaces() override;

std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;

return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;

return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
return return_type::OK;
}

protected:
/// Use standard interfaces for joints because they are relevant for dynamic behavior
/**
* By splitting the standard interfaces from other type, the users are able to inherit this
* class and simply create small "simulation" with desired dynamic behavior.
* The advantage over using Gazebo is that enables "quick & dirty" tests of robot's URDF and
* controllers.
*/
const std::vector<std::string> standard_interfaces_ = {
hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY,
hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT};

const size_t POSITION_INTERFACE_INDEX = 0;

struct MimicJoint
{
std::size_t joint_index;
std::size_t mimicked_joint_index;
double multiplier = 1.0;
};
std::vector<MimicJoint> mimic_joints_;

/// The size of this vector is (standard_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> joint_commands_;
std::vector<std::vector<double>> joint_states_;

std::vector<std::string> other_interfaces_;
/// The size of this vector is (other_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> other_commands_;
std::vector<std::vector<double>> other_states_;

std::vector<std::string> sensor_interfaces_;
/// The size of this vector is (sensor_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> sensor_fake_commands_;
std::vector<std::vector<double>> sensor_states_;

std::vector<std::string> gpio_interfaces_;
/// The size of this vector is (gpio_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> gpio_fake_commands_;
std::vector<std::vector<double>> gpio_commands_;
std::vector<std::vector<double>> gpio_states_;

private:
template <typename HandleType>
bool get_interface(
const std::string & name, const std::vector<std::string> & interface_list,
const std::string & interface_name, const size_t vector_index,
std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);

void initialize_storage_vectors(
std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
const std::vector<std::string> & interfaces);

template <typename InterfaceType>
bool populate_interfaces(
const std::vector<hardware_interface::ComponentInfo> & components,
std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
std::vector<InterfaceType> & target_interfaces, bool using_state_interfaces);

bool use_fake_gpio_command_interfaces_;
bool use_fake_sensor_command_interfaces_;

double position_state_following_offset_;
std::string custom_interface_with_following_offset_;
size_t index_custom_interface_with_following_offset_;
};
[[deprecated]] using GenericSystem = mock_components::GenericSystem;

typedef GenericSystem GenericRobot;
[[deprecated]] using GenericSystem = GenericRobot;

} // namespace fake_components

Expand Down
122 changes: 122 additions & 0 deletions hardware_interface/include/mock_components/generic_system.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,122 @@
// Copyright (c) 2021 PickNik, Inc.
//
// 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.
//
// Author: Jafar Abdi, Denis Stogl

#ifndef MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
#define MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_

#include <string>
#include <vector>

#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"

using hardware_interface::return_type;

namespace mock_components
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class HARDWARE_INTERFACE_PUBLIC GenericSystem : public hardware_interface::SystemInterface
{
public:
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;

std::vector<hardware_interface::StateInterface> export_state_interfaces() override;

std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;

return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;

return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
return return_type::OK;
}

protected:
/// Use standard interfaces for joints because they are relevant for dynamic behavior
/**
* By splitting the standard interfaces from other type, the users are able to inherit this
* class and simply create small "simulation" with desired dynamic behavior.
* The advantage over using Gazebo is that enables "quick & dirty" tests of robot's URDF and
* controllers.
*/
const std::vector<std::string> standard_interfaces_ = {
hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY,
hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT};

const size_t POSITION_INTERFACE_INDEX = 0;

struct MimicJoint
{
std::size_t joint_index;
std::size_t mimicked_joint_index;
double multiplier = 1.0;
};
std::vector<MimicJoint> mimic_joints_;

/// The size of this vector is (standard_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> joint_commands_;
std::vector<std::vector<double>> joint_states_;

std::vector<std::string> other_interfaces_;
/// The size of this vector is (other_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> other_commands_;
std::vector<std::vector<double>> other_states_;

std::vector<std::string> sensor_interfaces_;
/// The size of this vector is (sensor_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> sensor_fake_commands_;
std::vector<std::vector<double>> sensor_states_;

std::vector<std::string> gpio_interfaces_;
/// The size of this vector is (gpio_interfaces_.size() x nr_joints)
std::vector<std::vector<double>> gpio_fake_commands_;
std::vector<std::vector<double>> gpio_commands_;
std::vector<std::vector<double>> gpio_states_;

private:
template <typename HandleType>
bool get_interface(
const std::string & name, const std::vector<std::string> & interface_list,
const std::string & interface_name, const size_t vector_index,
std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);

void initialize_storage_vectors(
std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
const std::vector<std::string> & interfaces);

template <typename InterfaceType>
bool populate_interfaces(
const std::vector<hardware_interface::ComponentInfo> & components,
std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
std::vector<InterfaceType> & target_interfaces, bool using_state_interfaces);

bool use_fake_gpio_command_interfaces_;
bool use_fake_sensor_command_interfaces_;

double position_state_following_offset_;
std::string custom_interface_with_following_offset_;
size_t index_custom_interface_with_following_offset_;
};

typedef GenericSystem GenericRobot;

} // namespace mock_components

#endif // MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
Loading

0 comments on commit 1967cfa

Please sign in to comment.