Skip to content

Commit

Permalink
Merge branch 'master' into integrate/pal_statistics
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jan 15, 2025
2 parents d398ea7 + 00c7088 commit b72f313
Show file tree
Hide file tree
Showing 32 changed files with 136 additions and 72 deletions.
5 changes: 5 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.24.0 (2025-01-13)
-------------------
* Trigger shutdown transition in destructor (`#1979 <https://github.com/ros-controls/ros2_control/issues/1979>`_)
* Contributors: Christoph Fröhlich

4.23.0 (2024-12-29)
-------------------
* Remove boilerplate visibility macros (`#1972 <https://github.com/ros-controls/ros2_control/issues/1972>`_)
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.23.0</version>
<version>4.24.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: 6 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.24.0 (2025-01-13)
-------------------
* [CM] Remove obsolete ControllerMock from the tests (`#1990 <https://github.com/ros-controls/ros2_control/issues/1990>`_)
* Initialize robot description in ControllerManager (`#1983 <https://github.com/ros-controls/ros2_control/issues/1983>`_)
* Contributors: Dominic Reber, Wiktor Bajor

4.23.0 (2024-12-29)
-------------------
* Remove boilerplate visibility macros (`#1972 <https://github.com/ros-controls/ros2_control/issues/1972>`_)
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.23.0</version>
<version>4.24.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
6 changes: 0 additions & 6 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,10 +226,4 @@ class ControllerManagerRunner
ControllerManagerFixture<CtrlMgr> * cmf_;
};

class ControllerMock : public controller_interface::ControllerInterface
{
public:
MOCK_METHOD0(update, controller_interface::return_type(void));
};

#endif // CONTROLLER_MANAGER_TEST_COMMON_HPP_
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.24.0 (2025-01-13)
-------------------

4.23.0 (2024-12-29)
-------------------

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.23.0</version>
<version>4.24.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
7 changes: 7 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.24.0 (2025-01-13)
-------------------
* Add missing link of mock_components to hardware_interface (`#1992 <https://github.com/ros-controls/ros2_control/issues/1992>`_)
* Using urdf/model.hpp for rolling (`#1978 <https://github.com/ros-controls/ros2_control/issues/1978>`_)
* Remove visibility include from docs (`#1975 <https://github.com/ros-controls/ros2_control/issues/1975>`_)
* Contributors: Christoph Fröhlich, Silvio Traversaro, verma nakul

4.23.0 (2024-12-29)
-------------------
* Remove boilerplate visibility macros (`#1972 <https://github.com/ros-controls/ros2_control/issues/1972>`_)
Expand Down
1 change: 1 addition & 0 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ target_include_directories(mock_components PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/hardware_interface>
)
target_link_libraries(mock_components PUBLIC hardware_interface)
ament_target_dependencies(mock_components PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

pluginlib_export_plugin_description_file(
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.23.0</version>
<version>4.24.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
3 changes: 3 additions & 0 deletions hardware_interface_testing/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package hardware_interface_testing
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.24.0 (2025-01-13)
-------------------

4.23.0 (2024-12-29)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion hardware_interface_testing/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_testing</name>
<version>4.23.0</version>
<version>4.24.0</version>
<description>ros2_control hardware interface testing</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
7 changes: 7 additions & 0 deletions joint_limits/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package joint_limits
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.24.0 (2025-01-13)
-------------------
* Return strong type for joint_limits helpers (`#1981 <https://github.com/ros-controls/ros2_control/issues/1981>`_)
* Trigger shutdown transition in destructor (`#1979 <https://github.com/ros-controls/ros2_control/issues/1979>`_)
* Add joint limiter interface plugins to enforce limits defined in the URDF (`#1526 <https://github.com/ros-controls/ros2_control/issues/1526>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota, Wiktor Bajor

4.23.0 (2024-12-29)
-------------------
* Remove boilerplate visibility macros (`#1972 <https://github.com/ros-controls/ros2_control/issues/1972>`_)
Expand Down
17 changes: 17 additions & 0 deletions joint_limits/include/joint_limits/data_structures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,30 @@
#ifndef JOINT_LIMITS__DATA_STRUCTURES_HPP_
#define JOINT_LIMITS__DATA_STRUCTURES_HPP_

#include <limits>
#include <memory>
#include <optional>
#include <string>

#define DEFINE_LIMIT_STRUCT(LimitType) \
struct LimitType \
{ \
LimitType(double minimum_value, double maximum_value) \
: lower_limit(minimum_value), upper_limit(maximum_value) \
{ \
} \
double lower_limit = -std::numeric_limits<double>::infinity(); \
double upper_limit = std::numeric_limits<double>::infinity(); \
};

namespace joint_limits
{

DEFINE_LIMIT_STRUCT(PositionLimits);
DEFINE_LIMIT_STRUCT(VelocityLimits);
DEFINE_LIMIT_STRUCT(EffortLimits);
DEFINE_LIMIT_STRUCT(AccelerationLimits);

struct JointControlInterfacesData
{
std::string joint_name;
Expand Down
9 changes: 5 additions & 4 deletions joint_limits/include/joint_limits/joint_limits_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <optional>
#include <string>
#include <utility>
#include "joint_limits/data_structures.hpp"
#include "joint_limits/joint_limits.hpp"

namespace joint_limits
Expand All @@ -46,7 +47,7 @@ bool is_limited(double value, double min, double max);
* @param dt The time step.
* @return The position limits, first is the lower limit and second is the upper limit.
*/
std::pair<double, double> compute_position_limits(
PositionLimits compute_position_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_vel,
const std::optional<double> & prev_command_pos, double dt);

Expand All @@ -59,7 +60,7 @@ std::pair<double, double> compute_position_limits(
* @param dt The time step.
* @return The velocity limits, first is the lower limit and second is the upper limit.
*/
std::pair<double, double> compute_velocity_limits(
VelocityLimits compute_velocity_limits(
const std::string & joint_name, const joint_limits::JointLimits & limits,
const double & desired_vel, const std::optional<double> & act_pos,
const std::optional<double> & prev_command_vel, double dt);
Expand All @@ -72,7 +73,7 @@ std::pair<double, double> compute_velocity_limits(
* @param dt The time step.
* @return The effort limits, first is the lower limit and second is the upper limit.
*/
std::pair<double, double> compute_effort_limits(
EffortLimits compute_effort_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_pos,
const std::optional<double> & act_vel, double /*dt*/);

Expand All @@ -84,7 +85,7 @@ std::pair<double, double> compute_effort_limits(
* @param actual_velocity The actual velocity of the joint.
* @return The acceleration limits, first is the lower limit and second is the upper limit.
*/
std::pair<double, double> compute_acceleration_limits(
AccelerationLimits compute_acceleration_limits(
const JointLimits & limits, double desired_acceleration, std::optional<double> actual_velocity);

} // namespace joint_limits
Expand Down
2 changes: 1 addition & 1 deletion joint_limits/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>joint_limits</name>
<version>4.23.0</version>
<version>4.24.0</version>
<description>Package with interfaces for handling of joint limits in controllers or in hardware. The package also implements Saturation Joint Limiter for position-velocity-acceleration set and other individual interfaces.</description>

<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
Expand Down
61 changes: 31 additions & 30 deletions joint_limits/src/joint_limits_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,22 +26,22 @@ namespace internal
/**
* @brief Check if the limits are in the correct order and swap them if they are not.
*/
void check_and_swap_limits(std::pair<double, double> & limits)
void check_and_swap_limits(double & lower_limit, double & upper_limit)
{
if (limits.first > limits.second)
if (lower_limit > upper_limit)
{
std::swap(limits.first, limits.second);
std::swap(lower_limit, upper_limit);
}
}
} // namespace internal

bool is_limited(double value, double min, double max) { return value < min || value > max; }

std::pair<double, double> compute_position_limits(
PositionLimits compute_position_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_vel,
const std::optional<double> & prev_command_pos, double dt)
{
std::pair<double, double> pos_limits({limits.min_position, limits.max_position});
PositionLimits pos_limits(limits.min_position, limits.max_position);
if (limits.has_velocity_limits)
{
const double act_vel_abs = act_vel.has_value() ? std::fabs(act_vel.value()) : 0.0;
Expand All @@ -50,28 +50,28 @@ std::pair<double, double> compute_position_limits(
: limits.max_velocity;
const double max_vel = std::min(limits.max_velocity, delta_vel);
const double delta_pos = max_vel * dt;
pos_limits.first = std::max(prev_command_pos.value() - delta_pos, pos_limits.first);
pos_limits.second = std::min(prev_command_pos.value() + delta_pos, pos_limits.second);
pos_limits.lower_limit = std::max(prev_command_pos.value() - delta_pos, pos_limits.lower_limit);
pos_limits.upper_limit = std::min(prev_command_pos.value() + delta_pos, pos_limits.upper_limit);
}
internal::check_and_swap_limits(pos_limits);
internal::check_and_swap_limits(pos_limits.lower_limit, pos_limits.upper_limit);
return pos_limits;
}

std::pair<double, double> compute_velocity_limits(
VelocityLimits compute_velocity_limits(
const std::string & joint_name, const joint_limits::JointLimits & limits,
const double & desired_vel, const std::optional<double> & act_pos,
const std::optional<double> & prev_command_vel, double dt)
{
const double max_vel =
limits.has_velocity_limits ? limits.max_velocity : std::numeric_limits<double>::infinity();
std::pair<double, double> vel_limits({-max_vel, max_vel});
VelocityLimits vel_limits(-max_vel, max_vel);
if (limits.has_position_limits && act_pos.has_value())
{
const double actual_pos = act_pos.value();
const double max_vel_with_pos_limits = (limits.max_position - actual_pos) / dt;
const double min_vel_with_pos_limits = (limits.min_position - actual_pos) / dt;
vel_limits.first = std::max(min_vel_with_pos_limits, vel_limits.first);
vel_limits.second = std::min(max_vel_with_pos_limits, vel_limits.second);
vel_limits.lower_limit = std::max(min_vel_with_pos_limits, vel_limits.lower_limit);
vel_limits.upper_limit = std::min(max_vel_with_pos_limits, vel_limits.upper_limit);

if (actual_pos > limits.max_position || actual_pos < limits.min_position)
{
Expand All @@ -88,7 +88,7 @@ std::pair<double, double> compute_velocity_limits(
"further into bounds with vel %.5f: '%s'. Joint velocity limits will be "
"restrictred to zero.",
actual_pos, limits.min_position, limits.max_position, desired_vel, joint_name.c_str());
vel_limits = {0.0, 0.0};
vel_limits = VelocityLimits(0.0, 0.0);
}
// If the joint reports a position way out of bounds, then it would mean something is
// extremely wrong, so no velocity command should be allowed as it might damage the robot
Expand All @@ -101,72 +101,73 @@ std::pair<double, double> compute_velocity_limits(
"Joint position is out of bounds for the joint : '%s'. Joint velocity limits will be "
"restricted to zero.",
joint_name.c_str());
vel_limits = {0.0, 0.0};
vel_limits = VelocityLimits(0.0, 0.0);
}
}
}
if (limits.has_acceleration_limits && prev_command_vel.has_value())
{
const double delta_vel = limits.max_acceleration * dt;
vel_limits.first = std::max(prev_command_vel.value() - delta_vel, vel_limits.first);
vel_limits.second = std::min(prev_command_vel.value() + delta_vel, vel_limits.second);
vel_limits.lower_limit = std::max(prev_command_vel.value() - delta_vel, vel_limits.lower_limit);
vel_limits.upper_limit = std::min(prev_command_vel.value() + delta_vel, vel_limits.upper_limit);
}
internal::check_and_swap_limits(vel_limits);
internal::check_and_swap_limits(vel_limits.lower_limit, vel_limits.upper_limit);
return vel_limits;
}

std::pair<double, double> compute_effort_limits(
EffortLimits compute_effort_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_pos,
const std::optional<double> & act_vel, double /*dt*/)
{
const double max_effort =
limits.has_effort_limits ? limits.max_effort : std::numeric_limits<double>::infinity();
std::pair<double, double> eff_limits({-max_effort, max_effort});
EffortLimits eff_limits(-max_effort, max_effort);
if (limits.has_position_limits && act_pos.has_value() && act_vel.has_value())
{
if ((act_pos.value() <= limits.min_position) && (act_vel.value() <= 0.0))
{
eff_limits.first = 0.0;
eff_limits.lower_limit = 0.0;
}
else if ((act_pos.value() >= limits.max_position) && (act_vel.value() >= 0.0))
{
eff_limits.second = 0.0;
eff_limits.upper_limit = 0.0;
}
}
if (limits.has_velocity_limits && act_vel.has_value())
{
if (act_vel.value() < -limits.max_velocity)
{
eff_limits.first = 0.0;
eff_limits.lower_limit = 0.0;
}
else if (act_vel.value() > limits.max_velocity)
{
eff_limits.second = 0.0;
eff_limits.upper_limit = 0.0;
}
}
internal::check_and_swap_limits(eff_limits);
internal::check_and_swap_limits(eff_limits.lower_limit, eff_limits.upper_limit);
return eff_limits;
}

std::pair<double, double> compute_acceleration_limits(
AccelerationLimits compute_acceleration_limits(
const joint_limits::JointLimits & limits, double desired_acceleration,
std::optional<double> actual_velocity)
{
std::pair<double, double> acc_or_dec_limits(
AccelerationLimits acc_or_dec_limits(
-std::numeric_limits<double>::infinity(), std::numeric_limits<double>::infinity());
if (
limits.has_deceleration_limits &&
((desired_acceleration < 0 && actual_velocity && actual_velocity.value() > 0) ||
(desired_acceleration > 0 && actual_velocity && actual_velocity.value() < 0)))
{
acc_or_dec_limits.first = -limits.max_deceleration;
acc_or_dec_limits.second = limits.max_deceleration;
acc_or_dec_limits.lower_limit = -limits.max_deceleration;
acc_or_dec_limits.upper_limit = limits.max_deceleration;
}
else if (limits.has_acceleration_limits)
{
acc_or_dec_limits.first = -limits.max_acceleration;
acc_or_dec_limits.second = limits.max_acceleration;
acc_or_dec_limits.lower_limit = -limits.max_acceleration;
acc_or_dec_limits.upper_limit = limits.max_acceleration;
}
internal::check_and_swap_limits(acc_or_dec_limits.lower_limit, acc_or_dec_limits.upper_limit);
return acc_or_dec_limits;
}

Expand Down
Loading

0 comments on commit b72f313

Please sign in to comment.