Skip to content

Commit

Permalink
code review suggestions and:
Browse files Browse the repository at this point in the history
* components check for export of interfaces
* change intefaces to allow custom export and test
  • Loading branch information
mamueluth committed Jan 23, 2024
1 parent 4f81b55 commit 720e11f
Show file tree
Hide file tree
Showing 19 changed files with 673 additions and 356 deletions.
4 changes: 4 additions & 0 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,10 @@ if(BUILD_TESTING)
target_link_libraries(test_component_interfaces hardware_interface)
ament_target_dependencies(test_component_interfaces ros2_control_test_assets)

ament_add_gmock(test_component_interfaces_custom_export test/test_component_interfaces_custom_export.cpp)
target_link_libraries(test_component_interfaces_custom_export hardware_interface)
ament_target_dependencies(test_component_interfaces_custom_export ros2_control_test_assets)

ament_add_gmock(test_component_parser test/test_component_parser.cpp)
target_link_libraries(test_component_parser hardware_interface)
ament_target_dependencies(test_component_parser ros2_control_test_assets)
Expand Down
16 changes: 2 additions & 14 deletions hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,23 +64,11 @@ class Actuator final
HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & error();

[[deprecated(
"Replaced by vector<std::shared_ptr<StateInterface>> on_export_state_interfaces() method. "
"Exporting is handled by the Framework.")]] HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface>
export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces();

[[deprecated(
"Replaced by vector<std::shared_ptr<CommandInterface>> on_export_state_interfaces() method. "
"Exporting is handled by the Framework.")]] HARDWARE_INTERFACE_PUBLIC
std::vector<CommandInterface>
export_command_interfaces();
std::vector<StateInterfaceSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<std::shared_ptr<CommandInterface>> on_export_command_interfaces();
std::vector<CommandInterfaceSharedPtr> export_command_interfaces();

HARDWARE_INTERFACE_PUBLIC
return_type prepare_command_mode_switch(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <map>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -136,20 +137,18 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod

/// Exports all state interfaces for this hardware interface.
/**
* Default implementation for exporting the StateInterfaces. The StateInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the system_interface.
*
* If overwritten:
* The state interfaces have to be created and transferred according
* to the hardware info passed in for the configuration.
* Old way of exporting the StateInterfaces. If a empty vector is returned then
* the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned
* then the exporting of the StateInterfaces is only done with this function and the ownership is
* transferred to the resource manager. The set_command(...), get_command(...), ..., can then not
* be used.
*
* Note the ownership over the state interfaces is transferred to the caller.
*
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<std::shared_ptr<StateInterface>> on_export_state_interfaces() method. "
"Replaced by vector<StateInterfaceSharedPtr> on_export_state_interfaces() method. "
"Exporting is "
"handled "
"by the Framework.")]] virtual std::vector<StateInterface>
Expand All @@ -160,33 +159,41 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
return {};
}

std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces()
/**
* Default implementation for exporting the StateInterfaces. The StateInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the actuator_interface.
*
* \return vector of shared pointers to the created and stored StateInterfaces
*/
virtual std::vector<StateInterfaceSharedPtr> on_export_state_interfaces()
{
std::vector<std::shared_ptr<StateInterface>> state_interfaces;
std::vector<StateInterfaceSharedPtr> state_interfaces;
state_interfaces.reserve(joint_state_interfaces_.size());

for (const auto & [name, descr] : joint_state_interfaces_)
{
actuator_states_.insert(std::make_pair(name, std::make_shared<StateInterface>(descr)));
state_interfaces.push_back(actuator_states_.at(name));
auto state_interface = std::make_shared<StateInterface>(descr);
actuator_states_.insert(std::make_pair(name, state_interface));
state_interfaces.push_back(state_interface);
}
return state_interfaces;
}

/// Exports all command interfaces for this hardware interface.
/**
* Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the system_interface.
*
* The command interfaces have to be created and transferred according
* to the hardware info passed in for the configuration.
* Old way of exporting the CommandInterfaces. If a empty vector is returned then
* the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is
* returned then the exporting of the CommandInterfaces is only done with this function and the
* ownership is transferred to the resource manager. The set_command(...), get_command(...), ...,
* can then not be used.
*
* Note the ownership over the state interfaces is transferred to the caller.
*
* \return vector of command interfaces
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<std::shared_ptr<CommandInterface>> on_export_command_interfaces() method. "
"Replaced by vector<CommandInterfaceSharedPtr> on_export_command_interfaces() method. "
"Exporting is "
"handled "
"by the Framework.")]] virtual std::vector<CommandInterface>
Expand All @@ -197,15 +204,23 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
return {};
}

std::vector<std::shared_ptr<CommandInterface>> on_export_command_interfaces()
/**
* Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the actuator_interface.
*
* \return vector of shared pointers to the created and stored CommandInterfaces
*/
virtual std::vector<CommandInterfaceSharedPtr> on_export_command_interfaces()
{
std::vector<std::shared_ptr<CommandInterface>> command_interfaces;
std::vector<CommandInterfaceSharedPtr> command_interfaces;
command_interfaces.reserve(joint_command_interfaces_.size());

for (const auto & [name, descr] : joint_command_interfaces_)
{
actuator_commands_.insert(std::make_pair(name, std::make_shared<CommandInterface>(descr)));
command_interfaces.push_back(actuator_commands_.at(name));
auto command_interface = std::make_shared<CommandInterface>(descr);
actuator_commands_.insert(std::make_pair(name, command_interface));
command_interfaces.push_back(command_interface);
}

return command_interfaces;
Expand Down Expand Up @@ -315,9 +330,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
std::map<std::string, InterfaceDescription> joint_state_interfaces_;
std::map<std::string, InterfaceDescription> joint_command_interfaces_;

private:
std::map<std::string, std::shared_ptr<StateInterface>> actuator_states_;
std::map<std::string, std::shared_ptr<CommandInterface>> actuator_commands_;
std::unordered_map<std::string, StateInterfaceSharedPtr> actuator_states_;
std::unordered_map<std::string, CommandInterfaceSharedPtr> actuator_commands_;

rclcpp_lifecycle::State lifecycle_state_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,5 @@ HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_gpio_command_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);

HARDWARE_INTERFACE_PUBLIC
bool parse_bool(const std::string & bool_string);

} // namespace hardware_interface
#endif // HARDWARE_INTERFACE__COMPONENT_PARSER_HPP_
7 changes: 6 additions & 1 deletion hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define HARDWARE_INTERFACE__HANDLE_HPP_

#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <variant>
Expand Down Expand Up @@ -43,7 +44,7 @@ class Handle
}

explicit Handle(const InterfaceDescription & interface_description)
: prefix_name_(interface_description.prefix_name),
: prefix_name_(interface_description.prefix_name_),
interface_name_(interface_description.interface_info.name)
{
// As soon as multiple datatypes are used in HANDLE_DATATYPE
Expand Down Expand Up @@ -135,6 +136,8 @@ class StateInterface : public Handle
using Handle::Handle;
};

using StateInterfaceSharedPtr = std::shared_ptr<StateInterface>;

class CommandInterface : public Handle
{
public:
Expand All @@ -155,6 +158,8 @@ class CommandInterface : public Handle
using Handle::Handle;
};

using CommandInterfaceSharedPtr = std::shared_ptr<CommandInterface>;

} // namespace hardware_interface

#endif // HARDWARE_INTERFACE__HANDLE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -108,15 +108,15 @@ struct TransmissionInfo
*/
struct InterfaceDescription
{
InterfaceDescription(const std::string & prefix_name_in, const InterfaceInfo & interface_info_in)
: prefix_name(prefix_name_in), interface_info(interface_info_in)
InterfaceDescription(const std::string & prefix_name, const InterfaceInfo & interface_info_in)
: prefix_name_(prefix_name), interface_info(interface_info_in)
{
}

/**
* Name of the interface defined by the user.
*/
std::string prefix_name;
std::string prefix_name_;

/**
* What type of component is exported: joint, sensor or gpio
Expand All @@ -128,7 +128,7 @@ struct InterfaceDescription
*/
InterfaceInfo interface_info;

std::string get_name() const { return prefix_name + "/" + interface_info.name; }
std::string get_name() const { return prefix_name_ + "/" + interface_info.name; }

std::string get_interface_type() const { return interface_info.name; }
};
Expand Down
8 changes: 1 addition & 7 deletions hardware_interface/include/hardware_interface/sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,14 +65,8 @@ class Sensor final
HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & error();

[[deprecated(
"Replaced by vector<std::shared_ptr<StateInterface>> on_export_state_interfaces() method. "
"Exporting is handled by the Framework.")]] HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface>
export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces();
std::vector<StateInterfaceSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::string get_name() const;
Expand Down
34 changes: 20 additions & 14 deletions hardware_interface/include/hardware_interface/sensor_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <map>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -121,20 +122,18 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI

/// Exports all state interfaces for this hardware interface.
/**
* Default implementation for exporting the StateInterfaces. The StateInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the system_interface.
*
* If overwritten:
* The state interfaces have to be created and transferred according
* to the hardware info passed in for the configuration.
* Old way of exporting the StateInterfaces. If a empty vector is returned then
* the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned
* then the exporting of the StateInterfaces is only done with this function and the ownership is
* transferred to the resource manager. The set_command(...), get_command(...), ..., can then not
* be used.
*
* Note the ownership over the state interfaces is transferred to the caller.
*
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<std::shared_ptr<StateInterface>> on_export_state_interfaces() method. "
"Replaced by vector<StateInterfaceSharedPtr> on_export_state_interfaces() method. "
"Exporting is handled "
"by the Framework.")]] virtual std::vector<StateInterface>
export_state_interfaces()
Expand All @@ -144,17 +143,25 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
return {};
}

std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces()
/**
* Default implementation for exporting the StateInterfaces. The StateInterfaces are created
* according to the InterfaceDescription. The memory accessed by the controllers and hardware is
* assigned here and resides in the sensor_interface.
*
* \return vector of shared pointers to the created and stored StateInterfaces
*/
virtual std::vector<StateInterfaceSharedPtr> on_export_state_interfaces()
{
std::vector<std::shared_ptr<StateInterface>> state_interfaces;
std::vector<StateInterfaceSharedPtr> state_interfaces;
state_interfaces.reserve(sensor_state_interfaces_.size());

for (const auto & [name, descr] : sensor_state_interfaces_)
{
// TODO(Manuel) maybe check for duplicates otherwise only the first appearance of "name" is
// inserted
sensor_states_.insert(std::make_pair(name, std::make_shared<StateInterface>(descr)));
state_interfaces.push_back(sensor_states_.at(name));
auto state_interface = std::make_shared<StateInterface>(descr);
sensor_states_.insert(std::make_pair(name, state_interface));
state_interfaces.push_back(state_interface);
}

return state_interfaces;
Expand Down Expand Up @@ -205,8 +212,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI

std::map<std::string, InterfaceDescription> sensor_state_interfaces_;

private:
std::map<std::string, std::shared_ptr<StateInterface>> sensor_states_;
std::unordered_map<std::string, StateInterfaceSharedPtr> sensor_states_;

rclcpp_lifecycle::State lifecycle_state_;
};
Expand Down
16 changes: 2 additions & 14 deletions hardware_interface/include/hardware_interface/system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,23 +65,11 @@ class System final
HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & error();

[[deprecated(
"Replaced by vector<std::shared_ptr<StateInterface>> on_export_state_interfaces() method. "
"Exporting is handled by the Framework.")]] HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface>
export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces();

[[deprecated(
"Replaced by vector<std::shared_ptr<CommandInterface>> on_export_state_interfaces() method. "
"Exporting is handled by the Framework.")]] HARDWARE_INTERFACE_PUBLIC
std::vector<CommandInterface>
export_command_interfaces();
std::vector<StateInterfaceSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<std::shared_ptr<CommandInterface>> on_export_command_interfaces();
std::vector<CommandInterfaceSharedPtr> export_command_interfaces();

HARDWARE_INTERFACE_PUBLIC
return_type prepare_command_mode_switch(
Expand Down
Loading

0 comments on commit 720e11f

Please sign in to comment.