Skip to content

Commit

Permalink
Merge branch 'master' into get_set_lifecylce_state
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Aug 22, 2024
2 parents 99a5d25 + dd352eb commit 1a26869
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 13 deletions.
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
2 changes: 1 addition & 1 deletion doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ 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 to false, to avoid getting influenced by global arguments.
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
4 changes: 1 addition & 3 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,8 @@ For details see the controller_manager section.
* Pass controller manager update rate on the init of the controller interface (`#1141 <https://github.com/ros-controls/ros2_control/pull/1141>`_)
* 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.
* 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.
* With (`#1683 <https://github.com/ros-controls/ros2_control/pull/1683>`_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 <https://github.com/ros-controls/ros2_control/pull/1240>`_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles.
* The controllers will now set ``use_global_arguments`` from NodeOptions 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
17 changes: 11 additions & 6 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,17 @@ class Handle
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)
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
Expand All @@ -53,14 +57,14 @@ class Handle
[[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 @@ -77,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 @@ -111,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 Down

0 comments on commit 1a26869

Please sign in to comment.