Skip to content

Commit

Permalink
Merge branch 'master' into make-cli-output-nicer28
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar committed Jul 23, 2024
2 parents 3a6f191 + 3bc4e45 commit 40c007a
Show file tree
Hide file tree
Showing 118 changed files with 489 additions and 798 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.14.0 (2024-07-23)
-------------------
* Unused header cleanup (`#1627 <https://github.com/ros-controls/ros2_control/issues/1627>`_)
* move critical variables to the private context (`#1623 <https://github.com/ros-controls/ros2_control/issues/1623>`_)
* Contributors: Henry Moore, Sai Kishor Kothakota

4.13.0 (2024-07-08)
-------------------
* [ControllerChaining] Export state interfaces from chainable controllers (`#1021 <https://github.com/ros-controls/ros2_control/issues/1021>`_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_HPP_

#include <memory>
#include <string>
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

Expand Down Expand Up @@ -258,12 +257,12 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
protected:
std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
unsigned int update_rate_ = 0;
bool is_async_ = false;
std::string urdf_ = "";

private:
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
unsigned int update_rate_ = 0;
bool is_async_ = false;
std::string urdf_ = "";
};

using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_

#include <limits>
#include <string>
#include <vector>

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.13.0</version>
<version>4.14.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
6 changes: 0 additions & 6 deletions controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,8 @@

#include "controller_interface/controller_interface.hpp"

#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
{
ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {}
Expand Down
1 change: 0 additions & 1 deletion controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,13 @@
#ifndef TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "controller_interface/chainable_controller_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_chainable_controller";
constexpr double INTERFACE_VALUE = 1989.0;
Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define TEST_CONTROLLER_INTERFACE_HPP_

#include "controller_interface/controller_interface.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_controller_interface";

Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_with_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <gtest/gtest.h>
#include <string>
#include "ament_index_cpp/get_package_prefix.hpp"
#include "rclcpp/rclcpp.hpp"

class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions
{
Expand Down
2 changes: 0 additions & 2 deletions controller_interface/test/test_controller_with_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,9 @@
#define TEST_CONTROLLER_WITH_OPTIONS_HPP_

#include <map>
#include <memory>
#include <string>

#include "controller_interface/controller_interface.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"

namespace controller_with_options
{
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_force_torque_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_FORCE_TORQUE_SENSOR_HPP_
#define TEST_FORCE_TORQUE_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/force_torque_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_imu_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_IMU_SENSOR_HPP_
#define TEST_IMU_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/imu_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,12 @@
#ifndef TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_
#define TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>

#include "geometry_msgs/msg/wrench.hpp"
#include "gmock/gmock.h"
#include "semantic_components/semantic_component_interface.hpp"

// implementing and friending so we can access member variables
Expand Down
8 changes: 8 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.14.0 (2024-07-23)
-------------------
* Unused header cleanup (`#1627 <https://github.com/ros-controls/ros2_control/issues/1627>`_)
* Remove noqa (`#1626 <https://github.com/ros-controls/ros2_control/issues/1626>`_)
* Fix controller starting with later load of robot description test (`#1624 <https://github.com/ros-controls/ros2_control/issues/1624>`_)
* [CM] Remove support for the description parameter and use only `robot_description` topic (`#1358 <https://github.com/ros-controls/ros2_control/issues/1358>`_)
* Contributors: Christoph Fröhlich, Dr. Denis, Henry Moore, Sai Kishor Kothakota

4.13.0 (2024-07-08)
-------------------
* Change the spamming checking interface ERROR to DEBUG (`#1605 <https://github.com/ros-controls/ros2_control/issues/1605>`_)
Expand Down
1 change: 1 addition & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ if(BUILD_TESTING)
)
target_link_libraries(test_controller_manager_urdf_passing
controller_manager
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
ament_target_dependencies(test_controller_manager_urdf_passing
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/controller_manager/launch_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def generate_load_controller_launch_description(
'unload_on_kill' LaunchArguments and a Node action that runs the controller_manager
spawner node to load and activate a controller
Examples # noqa: D416
Examples
--------
# Assuming the controller type and controller parameters are known to the controller_manager
generate_load_controller_launch_description('joint_state_broadcaster')
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ jitter, using a lowlatency kernel can improve things a lot with being really eas
Subscribers
-----------

~/robot_description [std_msgs::msg::String]
robot_description [std_msgs::msg::String]
String with the URDF xml, e.g., from ``robot_state_publisher``.
Reloading of the URDF is not supported yet.
All joints defined in the ``<ros2_control>``-tag have to be present in the URDF.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <map>
#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>
#include <utility>
#include <vector>
Expand All @@ -42,17 +41,12 @@
#include "controller_manager_msgs/srv/unload_controller.hpp"

#include "diagnostic_updater/diagnostic_updater.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/resource_manager.hpp"

#include "pluginlib/class_loader.hpp"

#include "rclcpp/executor.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

namespace controller_manager
Expand Down Expand Up @@ -356,7 +350,7 @@ class ControllerManager : public rclcpp::Node
std::vector<std::string> get_controller_names();
std::pair<std::string, std::string> split_command_interface(
const std::string & command_interface);
void subscribe_to_robot_description_topic();
void init_controller_manager();

/**
* Clear request lists used when switching controllers. The lists are shared between "callback"
Expand Down Expand Up @@ -585,6 +579,7 @@ class ControllerManager : public rclcpp::Node

std::string robot_description_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;

struct SwitchParams
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,10 @@
#ifndef CONTROLLER_MANAGER__CONTROLLER_SPEC_HPP_
#define CONTROLLER_MANAGER__CONTROLLER_SPEC_HPP_

#include <map>
#include <memory>
#include <string>
#include <vector>
#include "controller_interface/controller_interface.hpp"
#include "controller_interface/controller_interface_base.hpp"
#include "hardware_interface/controller_info.hpp"

namespace controller_manager
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.13.0</version>
<version>4.14.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
Loading

0 comments on commit 40c007a

Please sign in to comment.