Skip to content

Commit

Permalink
merge parser functions
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Jan 26, 2024
1 parent 95b31ee commit fd532bd
Show file tree
Hide file tree
Showing 6 changed files with 39 additions and 102 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
virtual void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_state_interface_descriptions =
parse_joint_state_interface_descriptions_from_hardware_info(hardware_info);
parse_state_interface_descriptions_from_hardware_info(hardware_info.joints);
for (const auto & description : joint_state_interface_descriptions)
{
joint_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand All @@ -128,7 +128,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
virtual void import_command_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_command_interface_descriptions =
parse_joint_command_interface_descriptions_from_hardware_info(hardware_info);
parse_command_interface_descriptions_from_hardware_info(hardware_info.joints);
for (const auto & description : joint_command_interface_descriptions)
{
joint_command_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
43 changes: 8 additions & 35 deletions hardware_interface/include/hardware_interface/component_parser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,49 +34,22 @@ HARDWARE_INTERFACE_PUBLIC
std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string & urdf);

/**
* \param[in] hw_info the hardware description
* \return vector filled with information about robot's SommandInterfaces for the joints
* \param[in] component_info information about a component (gpio, joint, sensor)
* \return vector filled with information about hardware's StateInterfaces for the component
* which are exported
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_joint_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);
std::vector<InterfaceDescription> parse_state_interface_descriptions_from_hardware_info(
const std::vector<ComponentInfo> & component_info);

/**
* \param[in] hw_info the hardware description
* \return vector filled with information about robot's SommandInterfaces for the sensors
* \param[in] component_info information about a component (gpio, joint, sensor)
* \return vector filled with information about hardware's CommandInterfaces for the component
* which are exported
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_sensor_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);

/**
* \param[in] hw_info the hardware description
* \return vector filled with information about robot's SommandInterfaces for the gpios
* which are exported
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_gpio_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);

/**
* \param[in] hw_info the hardware description
* \return vector filled with information about robot's CommandInterfaces for the joints
* which are exported
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_joint_command_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);

/**
* \param[in] hw_info the hardware description
* \return vector filled with information about robot's CommandInterfaces for the gpios
* which are exported
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<InterfaceDescription> parse_gpio_command_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info);
std::vector<InterfaceDescription> parse_command_interface_descriptions_from_hardware_info(
const std::vector<ComponentInfo> & component_info);

} // namespace hardware_interface
#endif // HARDWARE_INTERFACE__COMPONENT_PARSER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
virtual void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto sensor_state_interface_descriptions =
parse_sensor_state_interface_descriptions_from_hardware_info(hardware_info);
parse_state_interface_descriptions_from_hardware_info(hardware_info.sensors);
for (const auto & description : sensor_state_interface_descriptions)
{
sensor_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,19 +116,19 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_state_interface_descriptions =
parse_joint_state_interface_descriptions_from_hardware_info(hardware_info);
parse_state_interface_descriptions_from_hardware_info(hardware_info.joints);
for (const auto & description : joint_state_interface_descriptions)
{
joint_state_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto sensor_state_interface_descriptions =
parse_sensor_state_interface_descriptions_from_hardware_info(hardware_info);
parse_state_interface_descriptions_from_hardware_info(hardware_info.sensors);
for (const auto & description : sensor_state_interface_descriptions)
{
sensor_state_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto gpio_state_interface_descriptions =
parse_gpio_state_interface_descriptions_from_hardware_info(hardware_info);
parse_state_interface_descriptions_from_hardware_info(hardware_info.gpios);
for (const auto & description : gpio_state_interface_descriptions)
{
gpio_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand All @@ -142,13 +142,13 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
void import_command_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_command_interface_descriptions =
parse_joint_command_interface_descriptions_from_hardware_info(hardware_info);
parse_command_interface_descriptions_from_hardware_info(hardware_info.joints);
for (const auto & description : joint_command_interface_descriptions)
{
joint_command_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto gpio_command_interface_descriptions =
parse_gpio_command_interface_descriptions_from_hardware_info(hardware_info);
parse_command_interface_descriptions_from_hardware_info(hardware_info.gpios);
for (const auto & description : gpio_command_interface_descriptions)
{
gpio_command_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
72 changes: 18 additions & 54 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -614,74 +614,38 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
return hardware_info;
}

std::vector<InterfaceDescription> parse_joint_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info)
std::vector<InterfaceDescription> parse_state_interface_descriptions_from_hardware_info(
const std::vector<ComponentInfo> & component_info)
{
std::vector<InterfaceDescription> joint_state_interface_descriptions;
joint_state_interface_descriptions.reserve(hw_info.joints.size());
std::vector<InterfaceDescription> component_state_interface_descriptions;
component_state_interface_descriptions.reserve(component_info.size());

for (const auto & joint : hw_info.joints)
for (const auto & component : component_info)
{
for (const auto & state_interface : joint.state_interfaces)
for (const auto & state_interface : component.state_interfaces)
{
joint_state_interface_descriptions.emplace_back(
InterfaceDescription(joint.name, state_interface));
component_state_interface_descriptions.emplace_back(
InterfaceDescription(component.name, state_interface));
}
}
return joint_state_interface_descriptions;
return component_state_interface_descriptions;
}

std::vector<InterfaceDescription> parse_sensor_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info)
{
std::vector<InterfaceDescription> sensor_state_interface_descriptions;
sensor_state_interface_descriptions.reserve(hw_info.sensors.size());

for (const auto & sensor : hw_info.sensors)
{
for (const auto & state_interface : sensor.state_interfaces)
{
sensor_state_interface_descriptions.emplace_back(
InterfaceDescription(sensor.name, state_interface));
}
}
return sensor_state_interface_descriptions;
}

std::vector<InterfaceDescription> parse_gpio_state_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info)
{
std::vector<InterfaceDescription> gpio_state_interface_descriptions;
gpio_state_interface_descriptions.reserve(hw_info.gpios.size());

for (const auto & gpio : hw_info.gpios)
{
for (const auto & state_interface : gpio.state_interfaces)
{
gpio_state_interface_descriptions.emplace_back(
InterfaceDescription(gpio.name, state_interface));
}
}
return gpio_state_interface_descriptions;
}

std::vector<InterfaceDescription> parse_joint_command_interface_descriptions_from_hardware_info(
const HardwareInfo & hw_info)
std::vector<InterfaceDescription> parse_command_interface_descriptions_from_hardware_info(
const std::vector<ComponentInfo> & component_info)
{
std::vector<InterfaceDescription>
gpio_state_intejoint_command_interface_descriptionsrface_descriptions;
gpio_state_intejoint_command_interface_descriptionsrface_descriptions.reserve(
hw_info.joints.size());
std::vector<InterfaceDescription> component_command_interface_descriptions;
component_command_interface_descriptions.reserve(component_info.size());

for (const auto & joint : hw_info.joints)
for (const auto & component : component_info)
{
for (const auto & command_interface : joint.command_interfaces)
for (const auto & command_interface : component.command_interfaces)
{
gpio_state_intejoint_command_interface_descriptionsrface_descriptions.emplace_back(
InterfaceDescription(joint.name, command_interface));
component_command_interface_descriptions.emplace_back(
InterfaceDescription(component.name, command_interface));
}
}
return gpio_state_intejoint_command_interface_descriptionsrface_descriptions;
return component_command_interface_descriptions;
}

std::vector<InterfaceDescription> parse_gpio_command_interface_descriptions_from_hardware_info(
Expand Down
10 changes: 5 additions & 5 deletions hardware_interface/test/test_component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -684,7 +684,7 @@ TEST_F(TestComponentParser, parse_joint_state_interface_descriptions_from_hardwa
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);

const auto joint_state_descriptions =
parse_joint_state_interface_descriptions_from_hardware_info(control_hardware[0]);
parse_state_interface_descriptions_from_hardware_info(control_hardware[0].joints);
EXPECT_EQ(joint_state_descriptions[0].prefix_name, "joint1");
EXPECT_EQ(joint_state_descriptions[0].get_interface_type(), "position");
EXPECT_EQ(joint_state_descriptions[0].get_name(), "joint1/position");
Expand All @@ -703,7 +703,7 @@ TEST_F(TestComponentParser, parse_joint_command_interface_descriptions_from_hard
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);

const auto joint_command_descriptions =
parse_joint_command_interface_descriptions_from_hardware_info(control_hardware[0]);
parse_command_interface_descriptions_from_hardware_info(control_hardware[0].joints);
EXPECT_EQ(joint_command_descriptions[0].prefix_name, "joint1");
EXPECT_EQ(joint_command_descriptions[0].get_interface_type(), "position");
EXPECT_EQ(joint_command_descriptions[0].get_name(), "joint1/position");
Expand All @@ -725,7 +725,7 @@ TEST_F(TestComponentParser, parse_sensor_state_interface_descriptions_from_hardw
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);

const auto sensor_state_descriptions =
parse_sensor_state_interface_descriptions_from_hardware_info(control_hardware[0]);
parse_state_interface_descriptions_from_hardware_info(control_hardware[0].sensors);
EXPECT_EQ(sensor_state_descriptions[0].prefix_name, "sensor1");
EXPECT_EQ(sensor_state_descriptions[0].get_interface_type(), "roll");
EXPECT_EQ(sensor_state_descriptions[0].get_name(), "sensor1/roll");
Expand All @@ -750,7 +750,7 @@ TEST_F(TestComponentParser, parse_gpio_state_interface_descriptions_from_hardwar
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);

const auto gpio_state_descriptions =
parse_gpio_state_interface_descriptions_from_hardware_info(control_hardware[0]);
parse_state_interface_descriptions_from_hardware_info(control_hardware[0].gpios);
EXPECT_EQ(gpio_state_descriptions[0].prefix_name, "flange_analog_IOs");
EXPECT_EQ(gpio_state_descriptions[0].get_interface_type(), "analog_output1");
EXPECT_EQ(gpio_state_descriptions[0].get_name(), "flange_analog_IOs/analog_output1");
Expand All @@ -775,7 +775,7 @@ TEST_F(TestComponentParser, parse_gpio_command_interface_descriptions_from_hardw
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);

const auto gpio_state_descriptions =
parse_gpio_command_interface_descriptions_from_hardware_info(control_hardware[0]);
parse_command_interface_descriptions_from_hardware_info(control_hardware[0].gpios);
EXPECT_EQ(gpio_state_descriptions[0].prefix_name, "flange_analog_IOs");
EXPECT_EQ(gpio_state_descriptions[0].get_interface_type(), "analog_output1");
EXPECT_EQ(gpio_state_descriptions[0].get_name(), "flange_analog_IOs/analog_output1");
Expand Down

0 comments on commit fd532bd

Please sign in to comment.