Skip to content

Commit

Permalink
Merge branch 'master' into add/sw_joint_limiter
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Aug 28, 2024
2 parents b515464 + d200408 commit c4da2d0
Show file tree
Hide file tree
Showing 93 changed files with 2,588 additions and 1,104 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.16.0
rev: v3.17.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand Down Expand Up @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.28.6
rev: 0.29.1
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
2 changes: 0 additions & 2 deletions codecov.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@ fixes:
comment:
layout: "diff, flags, files"
behavior: default
ignore:
- "**/test"
flags:
unittests:
paths:
Expand Down
18 changes: 18 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,24 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.1 (2024-08-24)
-------------------

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)
-------------------

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 @@ -82,7 +82,8 @@ class AsyncControllerThread
TimePoint next_iteration_time =
TimePoint(std::chrono::nanoseconds(controller_->get_node()->now().nanoseconds()));

if (controller_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
if (
controller_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
auto const current_time = controller_->get_node()->now();
auto const measured_period = current_time - previous_time;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;

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

CONTROLLER_INTERFACE_PUBLIC
unsigned int get_update_rate() const;
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.16.1</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
5 changes: 3 additions & 2 deletions controller_interface/src/chainable_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ bool ChainableControllerInterface::set_chained_mode(bool chained_mode)
{
bool result = false;

if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
result = on_set_chained_mode(chained_mode);

Expand All @@ -112,7 +112,8 @@ bool ChainableControllerInterface::set_chained_mode(bool chained_mode)
get_node()->get_logger(),
"Can not change controller's chained mode because it is no in '%s' state. "
"Current state is '%s'.",
hardware_interface::lifecycle_state_names::UNCONFIGURED, get_state().label().c_str());
hardware_interface::lifecycle_state_names::UNCONFIGURED,
get_lifecycle_state().label().c_str());
}

return result;
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::configure()
// Then we don't need to do state-machine related checks.
//
// Other solution is to add check into the LifecycleNode if a transition is valid to trigger
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
update_rate_ = static_cast<unsigned int>(get_node()->get_parameter("update_rate").as_int());
is_async_ = get_node()->get_parameter("is_async").as_bool();
Expand All @@ -106,7 +106,7 @@ void ControllerInterfaceBase::release_interfaces()
state_interfaces_.clear();
}

const rclcpp_lifecycle::State & ControllerInterfaceBase::get_state() const
const rclcpp_lifecycle::State & ControllerInterfaceBase::get_lifecycle_state() const
{
return node_->get_current_state();
}
Expand Down
13 changes: 9 additions & 4 deletions controller_interface/test/test_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#include <gmock/gmock.h>
#include <memory>
#include <string>
#include <vector>

#include "rclcpp/executor_options.hpp"
#include "rclcpp/executors/multi_threaded_executor.hpp"
Expand Down Expand Up @@ -57,13 +59,16 @@ TEST(TestableControllerInterface, init)
TEST(TestableControllerInterface, setting_update_rate_in_configure)
{
// mocks the declaration of overrides parameters in a yaml file
char const * const argv[] = {"", "--ros-args", "-p", "update_rate:=2812"};
int argc = arrlen(argv);
rclcpp::init(argc, argv);
rclcpp::init(0, nullptr);

TestableControllerInterface controller;
// initialize, create node
const auto node_options = controller.define_custom_node_options();
auto node_options = controller.define_custom_node_options();
std::vector<std::string> node_options_arguments = node_options.arguments();
node_options_arguments.push_back("--ros-args");
node_options_arguments.push_back("-p");
node_options_arguments.push_back("update_rate:=2812");
node_options = node_options.arguments(node_options_arguments);
ASSERT_EQ(
controller.init(TEST_CONTROLLER_NAME, "", 1.0, "", node_options),
controller_interface::return_type::OK);
Expand Down
38 changes: 38 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,44 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.16.1 (2024-08-24)
-------------------
* propage a portion of global args to the controller nodes (`#1712 <https://github.com/ros-controls/ros2_control/issues/1712>`_)
* Contributors: Sai Kishor Kothakota

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>`_)
* Fix the namespaced controller_manager spawner + added tests (`#1640 <https://github.com/ros-controls/ros2_control/issues/1640>`_)
* CM: Add missing includes (`#1641 <https://github.com/ros-controls/ros2_control/issues/1641>`_)
* Fix rst markup (`#1642 <https://github.com/ros-controls/ros2_control/issues/1642>`_)
* Add a pytest launch file to test ros2_control_node (`#1636 <https://github.com/ros-controls/ros2_control/issues/1636>`_)
* [CM] Remove deprecated spawner args (`#1639 <https://github.com/ros-controls/ros2_control/issues/1639>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota

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
6 changes: 6 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ if(BUILD_TESTING)

ament_add_gmock(test_spawner_unspawner
test/test_spawner_unspawner.cpp
TIMEOUT 120
)
target_link_libraries(test_spawner_unspawner
controller_manager
Expand All @@ -209,6 +210,11 @@ if(BUILD_TESTING)
ament_target_dependencies(test_hardware_management_srvs
controller_manager_msgs
)

find_package(ament_cmake_pytest REQUIRED)
install(FILES test/test_ros2_control_node.yaml
DESTINATION test)
ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py)
endif()

install(
Expand Down
8 changes: 8 additions & 0 deletions controller_manager/controller_manager/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@
set_hardware_component_state,
switch_controllers,
unload_controller,
get_parameter_from_param_file,
set_controller_parameters,
set_controller_parameters_from_param_file,
bcolors,
)

__all__ = [
Expand All @@ -36,4 +40,8 @@
"set_hardware_component_state",
"switch_controllers",
"unload_controller",
"get_parameter_from_param_file",
"set_controller_parameters",
"set_controller_parameters_from_param_file",
"bcolors",
]
Loading

0 comments on commit c4da2d0

Please sign in to comment.