Skip to content

Commit

Permalink
Merge branch 'master' into add_parameters_to_interface_info
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Aug 23, 2024
2 parents 3fc561b + ecfec15 commit 157446a
Show file tree
Hide file tree
Showing 36 changed files with 354 additions and 35 deletions.
6 changes: 6 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.0 (2024-08-22)
-------------------
* Fix params_file typo in spawner and update release notes for use_global_arguments (`#1701 <https://github.com/ros-controls/ros2_control/issues/1701>`_)
* Avoid using the global arguments for internal controller nodes (`#1694 <https://github.com/ros-controls/ros2_control/issues/1694>`_)
* Contributors: Sai Kishor Kothakota

4.15.0 (2024-08-05)
-------------------

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -174,12 +174,11 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
{
// \note The versions conditioning is added here to support the source-compatibility with Humble
#if RCLCPP_VERSION_MAJOR >= 21
return rclcpp::NodeOptions().enable_logger_service(true).use_global_arguments(false);
return rclcpp::NodeOptions().enable_logger_service(true);
#else
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)
.use_global_arguments(false);
.automatically_declare_parameters_from_overrides(true);
#endif
}

Expand Down
2 changes: 1 addition & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>4.15.0</version>
<version>4.16.0</version>
<description>Description of controller_interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
15 changes: 15 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,21 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.0 (2024-08-22)
-------------------
* inform user what reason is for not setting rt policy, inform is policy (`#1705 <https://github.com/ros-controls/ros2_control/issues/1705>`_)
* Fix params_file typo in spawner and update release notes for use_global_arguments (`#1701 <https://github.com/ros-controls/ros2_control/issues/1701>`_)
* Fix spawner tests timeout (`#1692 <https://github.com/ros-controls/ros2_control/issues/1692>`_)
* Refactor spawner to be able to reuse code for ros2controlcli (`#1661 <https://github.com/ros-controls/ros2_control/issues/1661>`_)
* Robustify controller spawner and add integration test with many controllers (`#1501 <https://github.com/ros-controls/ros2_control/issues/1501>`_)
* Handle waiting in Spawner and align Hardware Spawner functionality (`#1562 <https://github.com/ros-controls/ros2_control/issues/1562>`_)
* Make list controller and list hardware components immediately visualize the state. (`#1606 <https://github.com/ros-controls/ros2_control/issues/1606>`_)
* [CI] Add coveragepy and remove ignore: test (`#1668 <https://github.com/ros-controls/ros2_control/issues/1668>`_)
* Fix spawner unload on kill test (`#1675 <https://github.com/ros-controls/ros2_control/issues/1675>`_)
* [CM] Add more logging for easier debugging (`#1645 <https://github.com/ros-controls/ros2_control/issues/1645>`_)
* refactor SwitchParams to fix the incosistencies in the spawner tests (`#1638 <https://github.com/ros-controls/ros2_control/issues/1638>`_)
* Contributors: Bence Magyar, Christoph Fröhlich, Dr. Denis, Felix Exner (fexner), Manuel Muth, Sai Kishor Kothakota

4.15.0 (2024-08-05)
-------------------
* Add missing include for executors (`#1653 <https://github.com/ros-controls/ros2_control/issues/1653>`_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,7 @@ def set_controller_parameters_from_param_file(
if parameter_file:
spawner_namespace = namespace if namespace else node.get_namespace()
set_controller_parameters(
node, controller_manager_name, controller_name, "param_file", parameter_file
node, controller_manager_name, controller_name, "params_file", parameter_file
)

controller_type = get_parameter_from_param_file(
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>4.15.0</version>
<version>4.16.0</version>
<description>Description of controller_manager</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
1 change: 1 addition & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2843,6 +2843,7 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
}

controller_node_options = controller_node_options.arguments(node_options_arguments);
controller_node_options.use_global_arguments(false);
return controller_node_options;
}

Expand Down
13 changes: 10 additions & 3 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <errno.h>
#include <chrono>
#include <memory>
#include <string>
Expand Down Expand Up @@ -51,10 +52,16 @@ int main(int argc, char ** argv)
{
RCLCPP_WARN(
cm->get_logger(),
"Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT "
"scheduling. See "
"Could not enable FIFO RT scheduling policy: with error number <%i>(%s). See "
"[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
"for details.");
"for details on how to enable realtime scheduling.",
errno, strerror(errno));
}
else
{
RCLCPP_INFO(
cm->get_logger(), "Successful set up FIFO RT scheduling policy with priority %i.",
kSchedPriority);
}

// for calculating sleep time
Expand Down
3 changes: 3 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.0 (2024-08-22)
-------------------

4.15.0 (2024-08-05)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>4.15.0</version>
<version>4.16.0</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
4 changes: 4 additions & 0 deletions doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@

Iron to Jazzy
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
controller_interface
********************
* The changes from `(PR #1694) <https://github.com/ros-controls/ros2_control/pull/1694>`__ will affect how the controllers will be loading the parameters. Defining parameters in a single yaml file and loading it to the controller_manager node alone will no longer work.
In order to load the parameters to the controllers properly, it is needed to use ``--param-file`` option from the spawner. This is because the controllers will now set ``use_global_arguments`` from `NodeOptions <https://docs.ros.org/en/rolling/p/rclcpp/generated/classrclcpp_1_1NodeOptions.html#_CPPv4N6rclcpp11NodeOptions20use_global_argumentsEb>`__ to false, to avoid getting influenced by global arguments.

controller_manager
******************
Expand Down
2 changes: 2 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ For details see the controller_manager section.
* A method to get node options to setup the controller node #api-breaking (`#1169 <https://github.com/ros-controls/ros2_control/pull/1169>`_)
* Export state interfaces from the chainable controller #api-breaking (`#1021 <https://github.com/ros-controls/ros2_control/pull/1021>`_)
* All chainable controllers must implement the method ``export_state_interfaces`` to export the state interfaces, similar to ``export_reference_interfaces`` method that is exporting the reference interfaces.
* The controllers will now set ``use_global_arguments`` from `NodeOptions <https://docs.ros.org/en/rolling/p/rclcpp/generated/classrclcpp_1_1NodeOptions.html#_CPPv4N6rclcpp11NodeOptions20use_global_argumentsEb>`__ to false, to avoid getting influenced by global arguments (Issue : `#1684 <https://github.com/ros-controls/ros2_control/issues/1684>`_) (`#1694 <https://github.com/ros-controls/ros2_control/pull/1694>`_).
From now on, in order to set the parameters to the controller, the ``--param-file`` option from spawner should be used.

controller_manager
******************
Expand Down
8 changes: 8 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.0 (2024-08-22)
-------------------
* Use handle_name\_ variable instead of allocating for every `get_name` call (`#1706 <https://github.com/ros-controls/ros2_control/issues/1706>`_)
* Introduce Creation of Handles with InterfaceDescription (variant support) (`#1679 <https://github.com/ros-controls/ros2_control/issues/1679>`_)
* Preparation of Handles for Variant Support (`#1678 <https://github.com/ros-controls/ros2_control/issues/1678>`_)
* [RM] Decouple read/write cycles of each component with mutex to not block other components (`#1646 <https://github.com/ros-controls/ros2_control/issues/1646>`_)
* Contributors: Manuel Muth, Sai Kishor Kothakota

4.15.0 (2024-08-05)
-------------------
* [RM] Add `get_hardware_info` method to the Hardware Components (`#1643 <https://github.com/ros-controls/ros2_control/issues/1643>`_)
Expand Down
18 changes: 18 additions & 0 deletions hardware_interface/include/hardware_interface/component_parser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,5 +32,23 @@ namespace hardware_interface
HARDWARE_INTERFACE_PUBLIC
std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string & urdf);

/**
* \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_state_interface_descriptions(
const std::vector<ComponentInfo> & component_info);

/**
* \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_command_interface_descriptions(
const std::vector<ComponentInfo> & component_info);

} // namespace hardware_interface
#endif // HARDWARE_INTERFACE__COMPONENT_PARSER_HPP_
45 changes: 32 additions & 13 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,11 @@
#ifndef HARDWARE_INTERFACE__HANDLE_HPP_
#define HARDWARE_INTERFACE__HANDLE_HPP_

#include <limits>
#include <string>
#include <variant>

#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/macros.hpp"

namespace hardware_interface
Expand All @@ -29,20 +31,40 @@ using HANDLE_DATATYPE = std::variant<double>;
class Handle
{
public:
[[deprecated("Use InterfaceDescription for initializing the Interface")]]

Handle(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: prefix_name_(prefix_name), interface_name_(interface_name), value_ptr_(value_ptr)
: prefix_name_(prefix_name),
interface_name_(interface_name),
handle_name_(prefix_name_ + "/" + interface_name_),
value_ptr_(value_ptr)
{
}

explicit Handle(const InterfaceDescription & interface_description)
: prefix_name_(interface_description.prefix_name),
interface_name_(interface_description.interface_info.name),
handle_name_(prefix_name_ + "/" + interface_name_)
{
// As soon as multiple datatypes are used in HANDLE_DATATYPE
// we need to initialize according the type passed in interface description
value_ = std::numeric_limits<double>::quiet_NaN();
value_ptr_ = std::get_if<double>(&value_);
}

[[deprecated("Use InterfaceDescription for initializing the Interface")]]

explicit Handle(const std::string & interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
: interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
{
}

[[deprecated("Use InterfaceDescription for initializing the Interface")]]

explicit Handle(const char * interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
: interface_name_(interface_name), handle_name_("/" + interface_name_), value_ptr_(nullptr)
{
}

Expand All @@ -59,12 +81,12 @@ class Handle
/// Returns true if handle references a value.
inline operator bool() const { return value_ptr_ != nullptr; }

const std::string get_name() const { return prefix_name_ + "/" + interface_name_; }
const std::string & get_name() const { return handle_name_; }

const std::string & get_interface_name() const { return interface_name_; }

[[deprecated(
"Replaced by get_name method, which is semantically more correct")]] const std::string
"Replaced by get_name method, which is semantically more correct")]] const std::string &
get_full_name() const
{
return get_name();
Expand Down Expand Up @@ -93,6 +115,7 @@ class Handle
protected:
std::string prefix_name_;
std::string interface_name_;
std::string handle_name_;
HANDLE_DATATYPE value_;
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
Expand All @@ -103,10 +126,8 @@ class Handle
class StateInterface : public Handle
{
public:
explicit StateInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: Handle(prefix_name, interface_name, value_ptr)
explicit StateInterface(const InterfaceDescription & interface_description)
: Handle(interface_description)
{
}

Expand All @@ -120,10 +141,8 @@ class StateInterface : public Handle
class CommandInterface : public Handle
{
public:
explicit CommandInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: Handle(prefix_name, interface_name, value_ptr)
explicit CommandInterface(const InterfaceDescription & interface_description)
: Handle(interface_description)
{
}
/// CommandInterface copy constructor is actively deleted.
Expand Down
39 changes: 37 additions & 2 deletions hardware_interface/include/hardware_interface/hardware_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ struct InterfaceInfo
std::string max;
/// (Optional) Initial value of the interface.
std::string initial_value;
/// (Optional) The datatype of the interface, e.g. "bool", "int". Used by GPIOs.
/// (Optional) The datatype of the interface, e.g. "bool", "int".
std::string data_type;
/// (Optional) If the handle is an array, the size of the array. Used by GPIOs.
/// (Optional) If the handle is an array, the size of the array.
int size;
/// (Optional) enable or disable the limits for the command interfaces
bool enable_limits;
Expand Down Expand Up @@ -130,6 +130,41 @@ struct TransmissionInfo
std::unordered_map<std::string, std::string> parameters;
};

/**
* This structure stores information about an interface for a specific hardware which should be
* instantiated internally.
*/
struct InterfaceDescription
{
InterfaceDescription(const std::string & prefix_name_in, const InterfaceInfo & interface_info_in)
: prefix_name(prefix_name_in),
interface_info(interface_info_in),
interface_name(prefix_name + "/" + interface_info.name)
{
}

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

/**
* Information about the Interface type (position, velocity,...) as well as limits and so on.
*/
InterfaceInfo interface_info;

/**
* Name of the interface
*/
std::string interface_name;

std::string get_prefix_name() const { return prefix_name; }

std::string get_interface_name() const { return interface_info.name; }

std::string get_name() const { return interface_name; }
};

/// This structure stores information about hardware defined in a robot's URDF.
struct HardwareInfo
{
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface</name>
<version>4.15.0</version>
<version>4.16.0</version>
<description>ros2_control hardware interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
34 changes: 34 additions & 0 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -912,4 +912,38 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
return hardware_info;
}

std::vector<InterfaceDescription> parse_state_interface_descriptions(
const std::vector<ComponentInfo> & component_info)
{
std::vector<InterfaceDescription> component_state_interface_descriptions;
component_state_interface_descriptions.reserve(component_info.size());

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

std::vector<InterfaceDescription> parse_command_interface_descriptions(
const std::vector<ComponentInfo> & component_info)
{
std::vector<InterfaceDescription> component_command_interface_descriptions;
component_command_interface_descriptions.reserve(component_info.size());

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

} // namespace hardware_interface
Loading

0 comments on commit 157446a

Please sign in to comment.