Skip to content

Commit

Permalink
Merge branch 'master' into improve/memory_allocation/buffer_variables
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jan 1, 2025
2 parents 58386ae + 53656e4 commit 636fdd0
Show file tree
Hide file tree
Showing 60 changed files with 323 additions and 647 deletions.
4 changes: 2 additions & 2 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.19.0
rev: v3.19.1
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand All @@ -63,7 +63,7 @@ repos:

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v19.1.4
rev: v19.1.5
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down
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.23.0 (2024-12-29)
-------------------
* Remove boilerplate visibility macros (`#1972 <https://github.com/ros-controls/ros2_control/issues/1972>`_)
* Semantic components cleanup (`#1940 <https://github.com/ros-controls/ros2_control/issues/1940>`_)
* Contributors: Bence Magyar, Wiktor Bajor

4.22.0 (2024-12-20)
-------------------
* Fixed typo. Added s to state_interfaces\_ (`#1930 <https://github.com/ros-controls/ros2_control/issues/1930>`_)
Expand Down
7 changes: 4 additions & 3 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
-Werror=missing-braces)
endif()

# using this instead of visibility macros
# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

set(THIS_PACKAGE_INCLUDE_DEPENDS
hardware_interface
rclcpp_lifecycle
Expand All @@ -29,9 +33,6 @@ target_include_directories(controller_interface PUBLIC
$<INSTALL_INTERFACE:include/controller_interface>
)
ament_target_dependencies(controller_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(controller_interface PRIVATE "CONTROLLER_INTERFACE_BUILDING_DLL")

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
#include "controller_interface/visibility_control.h"
#include "hardware_interface/handle.hpp"

namespace controller_interface
Expand All @@ -37,10 +36,8 @@ namespace controller_interface
class ChainableControllerInterface : public ControllerInterfaceBase
{
public:
CONTROLLER_INTERFACE_PUBLIC
ChainableControllerInterface();

CONTROLLER_INTERFACE_PUBLIC
virtual ~ChainableControllerInterface() = default;

/**
Expand All @@ -52,22 +49,16 @@ class ChainableControllerInterface : public ControllerInterfaceBase
* \param[in] period The measured time taken by the last control loop iteration
* \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
*/
CONTROLLER_INTERFACE_PUBLIC
return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) final;

CONTROLLER_INTERFACE_PUBLIC
bool is_chainable() const final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface::ConstSharedPtr> export_state_interfaces() final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::CommandInterface::SharedPtr> export_reference_interfaces() final;

CONTROLLER_INTERFACE_PUBLIC
bool set_chained_mode(bool chained_mode) final;

CONTROLLER_INTERFACE_PUBLIC
bool is_in_chained_mode() const final;

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,58 +19,50 @@
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
#include "controller_interface/visibility_control.h"
#include "hardware_interface/handle.hpp"

namespace controller_interface
{
class ControllerInterface : public controller_interface::ControllerInterfaceBase
{
public:
CONTROLLER_INTERFACE_PUBLIC
ControllerInterface();

CONTROLLER_INTERFACE_PUBLIC
virtual ~ControllerInterface() = default;

/**
* Controller is not chainable.
*
* \returns false.
*/
CONTROLLER_INTERFACE_PUBLIC
bool is_chainable() const final;

/**
* A non-chainable controller doesn't export any state interfaces.
*
* \returns empty list.
*/
CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface::ConstSharedPtr> export_state_interfaces() final;

/**
* Controller has no reference interfaces.
*
* \returns empty list.
*/
CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::CommandInterface::SharedPtr> export_reference_interfaces() final;

/**
* Controller is not chainable, therefore no chained mode can be set.
*
* \returns false.
*/
CONTROLLER_INTERFACE_PUBLIC
bool set_chained_mode(bool chained_mode) final;

/**
* Controller can not be in chained mode.
*
* \returns false.
*/
CONTROLLER_INTERFACE_PUBLIC
bool is_in_chained_mode() const final;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <utility>
#include <vector>

#include "controller_interface/visibility_control.h"
#include "realtime_tools/async_function_handler.hpp"

#include "hardware_interface/handle.hpp"
Expand Down Expand Up @@ -98,10 +97,8 @@ struct ControllerUpdateStatus
class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
{
public:
CONTROLLER_INTERFACE_PUBLIC
ControllerInterfaceBase() = default;

CONTROLLER_INTERFACE_PUBLIC
virtual ~ControllerInterfaceBase() = default;

/// Get configuration for controller's required command interfaces.
Expand All @@ -116,7 +113,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns configuration of command interfaces.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual InterfaceConfiguration command_interface_configuration() const = 0;

/// Get configuration for controller's required state interfaces.
Expand All @@ -133,7 +129,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns configuration of state interfaces.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual InterfaceConfiguration state_interface_configuration() const = 0;

/// Method that assigns the Loaned interfaces to the controller.
Expand All @@ -145,7 +140,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
* \param[in] command_interfaces vector of command interfaces to be assigned to the controller.
* \param[in] state_interfaces vector of state interfaces to be assigned to the controller.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual void assign_interfaces(
std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
Expand All @@ -154,10 +148,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
/**
* Method used by the controller_manager to release the interfaces from the controller.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual void release_interfaces();

CONTROLLER_INTERFACE_PUBLIC
return_type init(
const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
Expand All @@ -166,11 +158,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
/*
* Override default implementation for configure of LifecycleNode to get parameters.
*/
CONTROLLER_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & configure();

/// Extending interface with initialization method which is individual for each controller
CONTROLLER_INTERFACE_PUBLIC
virtual CallbackReturn on_init() = 0;

/**
Expand All @@ -182,7 +172,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
* \param[in] period The measured time since the last control loop iteration
* \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

/**
Expand All @@ -197,25 +186,18 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
* \returns ControllerUpdateStatus. The status contains information if the update was triggered
* successfully, the result of the update method and the execution duration of the update method.
*/
CONTROLLER_INTERFACE_PUBLIC
ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);

CONTROLLER_INTERFACE_PUBLIC
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();

CONTROLLER_INTERFACE_PUBLIC
std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;

CONTROLLER_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & get_lifecycle_state() const;

CONTROLLER_INTERFACE_PUBLIC
unsigned int get_update_rate() const;

CONTROLLER_INTERFACE_PUBLIC
bool is_async() const;

CONTROLLER_INTERFACE_PUBLIC
const std::string & get_robot_description() const;

/**
Expand All @@ -229,7 +211,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* @returns NodeOptions required for the configuration of the controller lifecycle node
*/
CONTROLLER_INTERFACE_PUBLIC
virtual rclcpp::NodeOptions define_custom_node_options() const
{
rclcpp::NodeOptions node_options;
Expand Down Expand Up @@ -272,7 +253,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns true is controller is chainable and false if it is not.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual bool is_chainable() const = 0;

/**
Expand All @@ -281,7 +261,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns list of command interfaces for preceding controllers.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
export_reference_interfaces() = 0;

Expand All @@ -291,7 +270,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns list of state interfaces for preceding controllers.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
export_state_interfaces() = 0;

Expand All @@ -303,7 +281,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns true if mode is switched successfully and false if not.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual bool set_chained_mode(bool chained_mode) = 0;

/// Get information if a controller is currently in chained mode.
Expand All @@ -314,7 +291,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*
* \returns true is controller is in chained mode and false if it is not.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual bool is_in_chained_mode() const = 0;

/**
Expand All @@ -327,7 +303,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
* If the controller is running in async mode, the method will wait for the current async update
* to finish. If the controller is not running in async mode, the method will do nothing.
*/
CONTROLLER_INTERFACE_PUBLIC
void wait_for_trigger_update_to_finish();

protected:
Expand Down
Loading

0 comments on commit 636fdd0

Please sign in to comment.