Skip to content

Commit c1b1865

Browse files
authored
Async params (#927)
* add is_async param to controller manager * handle is_async param for hw components * Remove std::terminate() call used for debugging * Remove whitespace * Remove empty line * use strcasecmp
1 parent 17d5ca0 commit c1b1865

File tree

6 files changed

+30
-0
lines changed

6 files changed

+30
-0
lines changed

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -153,6 +153,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
153153
CONTROLLER_INTERFACE_PUBLIC
154154
unsigned int get_update_rate() const;
155155

156+
CONTROLLER_INTERFACE_PUBLIC
157+
bool is_async() const;
158+
156159
/// Declare and initialize a parameter with a type.
157160
/**
158161
*
@@ -220,6 +223,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
220223
std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
221224
std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
222225
unsigned int update_rate_ = 0;
226+
bool is_async_ = false;
223227

224228
private:
225229
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;

controller_interface/src/controller_interface_base.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ return_type ControllerInterfaceBase::init(
3434
try
3535
{
3636
auto_declare<int>("update_rate", 0);
37+
auto_declare<bool>("is_async", false);
3738
}
3839
catch (const std::exception & e)
3940
{
@@ -84,6 +85,7 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::configure()
8485
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
8586
{
8687
update_rate_ = get_node()->get_parameter("update_rate").as_int();
88+
is_async_ = get_node()->get_parameter("is_async").as_bool();
8789
}
8890

8991
return get_node()->configure();

hardware_interface/include/hardware_interface/hardware_component_info.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,9 @@ struct HardwareComponentInfo
4242
/// Component pluginlib plugin name.
4343
std::string plugin_name;
4444

45+
/// Component is async
46+
bool is_async;
47+
4548
/// Component current state.
4649
rclcpp_lifecycle::State state;
4750

hardware_interface/include/hardware_interface/hardware_info.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ struct ComponentInfo
5454
std::string name;
5555
/// Type of the component: sensor, joint, or GPIO.
5656
std::string type;
57+
5758
/**
5859
* Name of the command interfaces that can be set, e.g. "position", "velocity", etc.
5960
* Used by joints and GPIOs.
@@ -106,6 +107,8 @@ struct HardwareInfo
106107
std::string name;
107108
/// Type of the hardware: actuator, sensor or system.
108109
std::string type;
110+
/// Component is async
111+
bool is_async;
109112
/// Name of the pluginlib plugin of the hardware that will be loaded.
110113
std::string hardware_plugin_name;
111114
/// (Optional) Key-value pairs for hardware parameters.

hardware_interface/src/component_parser.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@ constexpr const auto kTypeAttribute = "type";
4747
constexpr const auto kRoleAttribute = "role";
4848
constexpr const auto kReductionAttribute = "mechanical_reduction";
4949
constexpr const auto kOffsetAttribute = "offset";
50+
constexpr const auto kIsAsyncAttribute = "is_async";
51+
5052
} // namespace
5153

5254
namespace hardware_interface
@@ -211,6 +213,20 @@ std::string parse_data_type_attribute(const tinyxml2::XMLElement * elem)
211213
return data_type;
212214
}
213215

216+
/// Parse is_async attribute
217+
/**
218+
* Parses an XMLElement and returns the value of the is_async attribute.
219+
* Defaults to "false" if not specified.
220+
*
221+
* \param[in] elem XMLElement that has the data_type attribute.
222+
* \return boolean specifying the if the value read was true or false.
223+
*/
224+
bool parse_is_async_attribute(const tinyxml2::XMLElement * elem)
225+
{
226+
const tinyxml2::XMLAttribute * attr = elem->FindAttribute(kIsAsyncAttribute);
227+
return attr ? strcasecmp(attr->Value(), "true") == 0 : false;
228+
}
229+
214230
/// Search XML snippet from URDF for parameters.
215231
/**
216232
* \param[in] params_it pointer to the iterator where parameters info should be found
@@ -499,6 +515,7 @@ HardwareInfo parse_resource_from_xml(
499515
HardwareInfo hardware;
500516
hardware.name = get_attribute_value(ros2_control_it, kNameAttribute, kROS2ControlTag);
501517
hardware.type = get_attribute_value(ros2_control_it, kTypeAttribute, kROS2ControlTag);
518+
hardware.is_async = parse_is_async_attribute(ros2_control_it);
502519

503520
// Parse everything under ros2_control tag
504521
hardware.hardware_plugin_name = "";

hardware_interface/src/resource_manager.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,7 @@ class ResourceStorage
9797
component_info.name = hardware_info.name;
9898
component_info.type = hardware_info.type;
9999
component_info.plugin_name = hardware_info.hardware_plugin_name;
100+
component_info.is_async = hardware_info.is_async;
100101

101102
hardware_info_map_.insert(std::make_pair(component_info.name, component_info));
102103
hardware_used_by_controllers_.insert(

0 commit comments

Comments
 (0)