Skip to content

Commit

Permalink
Merge branch 'master' into add/cm/activity/topic
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Feb 19, 2025
2 parents a2b07d9 + 201d3a7 commit 0aa3494
Show file tree
Hide file tree
Showing 100 changed files with 2,924 additions and 1,095 deletions.
12 changes: 3 additions & 9 deletions .github/workflows/humble-abi-compatibility.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,6 @@ concurrency:

jobs:
abi_check:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- uses: ros-industrial/industrial_ci@master
env:
ROS_DISTRO: humble
ROS_REPO: testing
ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }}
NOT_TEST_BUILD: true
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master
with:
ros_distro: humble
8 changes: 5 additions & 3 deletions .github/workflows/humble-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: humble
upstream_workspace: ros2_control.humble.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.humble.repos
Expand All @@ -42,8 +42,10 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: humble
upstream_workspace: ros2_control.humble.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.humble.repos
downstream_workspace: | # build also the ros2_control packages
ros_controls.humble.repos
downstream.humble.repos
not_test_downstream: true
12 changes: 3 additions & 9 deletions .github/workflows/jazzy-abi-compatibility.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,6 @@ concurrency:

jobs:
abi_check:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- uses: ros-industrial/industrial_ci@master
env:
ROS_DISTRO: jazzy
ROS_REPO: testing
ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }}
NOT_TEST_BUILD: true
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master
with:
ros_distro: jazzy
8 changes: 5 additions & 3 deletions .github/workflows/jazzy-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.jazzy.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.jazzy.repos
Expand All @@ -42,8 +42,10 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.jazzy.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.jazzy.repos
downstream_workspace: | # build also the ros_controls packages
ros_controls.jazzy.repos
downstream.jazzy.repos
not_test_downstream: true
12 changes: 3 additions & 9 deletions .github/workflows/rolling-abi-compatibility.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,6 @@ concurrency:

jobs:
abi_check:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- uses: ros-industrial/industrial_ci@master
env:
ROS_DISTRO: rolling
ROS_REPO: testing
ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }}
NOT_TEST_BUILD: true
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-abi-check.yml@master
with:
ros_distro: rolling
8 changes: 5 additions & 3 deletions .github/workflows/rolling-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.${{ matrix.ROS_DISTRO }}.repos
Expand All @@ -50,8 +50,10 @@ jobs:
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos
# we don't test this repository, we just build it
# we don't test target_workspace, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.${{ matrix.ROS_DISTRO }}.repos
downstream_workspace: | # build also the ros_controls packages
ros_controls.${{ matrix.ROS_DISTRO }}.repos
downstream.${{ matrix.ROS_DISTRO }}.repos
not_test_downstream: true
8 changes: 4 additions & 4 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ repos:
args: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"]

- repo: https://github.com/psf/black
rev: 24.10.0
rev: 25.1.0
hooks:
- id: black
args: ["--line-length=99"]
Expand All @@ -63,7 +63,7 @@ repos:

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v19.1.5
rev: v19.1.7
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down Expand Up @@ -126,14 +126,14 @@ repos:
# Spellcheck in comments and docs
# skipping of *.svg files is not working...
- repo: https://github.com/codespell-project/codespell
rev: v2.3.0
rev: v2.4.1
hooks:
- id: codespell
args: ['--write-changes', '--uri-ignore-words-list=ist', '-L manuel']
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.30.0
rev: 0.31.1
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
11 changes: 11 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,17 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.26.0 (2025-02-07)
-------------------
* add a semantic command interface to "semantic_components" (`#1945 <https://github.com/ros-controls/ros2_control/issues/1945>`_)
* Contributors: Thibault Poignonec

4.25.0 (2025-01-29)
-------------------
* Use `target_compile_definitions` instead of installing test files (`#2009 <https://github.com/ros-controls/ros2_control/issues/2009>`_)
* Add GPS semantic component (`#2000 <https://github.com/ros-controls/ros2_control/issues/2000>`_)
* Contributors: Sai Kishor Kothakota, Wiktor Bajor

4.24.0 (2025-01-13)
-------------------
* Trigger shutdown transition in destructor (`#1979 <https://github.com/ros-controls/ros2_control/issues/1979>`_)
Expand Down
20 changes: 19 additions & 1 deletion controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,12 +87,30 @@ if(BUILD_TESTING)
ament_target_dependencies(test_pose_sensor
geometry_msgs
)

ament_add_gmock(test_gps_sensor test/test_gps_sensor.cpp)
target_link_libraries(test_gps_sensor
controller_interface
hardware_interface::hardware_interface
)

# Semantic component command interface tests

ament_add_gmock(test_semantic_component_command_interface
test/test_semantic_component_command_interface.cpp
)
target_link_libraries(test_semantic_component_command_interface
controller_interface
hardware_interface::hardware_interface
)

ament_add_gmock(test_led_rgb_device test/test_led_rgb_device.cpp)
target_link_libraries(test_led_rgb_device
controller_interface
hardware_interface::hardware_interface
)
ament_target_dependencies(test_led_rgb_device
std_msgs
)
endif()

install(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "realtime_tools/async_function_handler.hpp"

#include "hardware_interface/handle.hpp"
#include "hardware_interface/introspection.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"

Expand Down Expand Up @@ -305,6 +306,14 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
*/
void wait_for_trigger_update_to_finish();

std::string get_name() const;

/// Enable or disable introspection of the controller.
/**
* \param[in] enable Enable introspection if true, disable otherwise.
*/
void enable_introspection(bool enable);

protected:
std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
Expand All @@ -316,6 +325,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
bool is_async_ = false;
std::string urdf_ = "";
ControllerUpdateStats trigger_stats_;

protected:
pal_statistics::RegistrationsRAII stats_registrations_;
};

using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
{
if (existing_axes_[i])
{
forces[i] = state_interfaces_[interface_counter].get().get_value();
forces[i] = state_interfaces_[interface_counter].get().get_value<double>().value();
++interface_counter;
}
}
Expand All @@ -123,7 +123,7 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
{
if (existing_axes_[i + FORCES_SIZE])
{
torques[i] = state_interfaces_[torque_interface_counter].get().get_value();
torques[i] = state_interfaces_[torque_interface_counter].get().get_value<double>().value();
++torque_interface_counter;
}
}
Expand Down
28 changes: 20 additions & 8 deletions controller_interface/include/semantic_components/gps_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,10 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
*
* \return Status
*/
int8_t get_status() const { return static_cast<int8_t>(state_interfaces_[0].get().get_value()); }
int8_t get_status() const
{
return static_cast<int8_t>(state_interfaces_[0].get().template get_value<double>().value());
}

/**
* Return service used by GPS e.g. fix/no_fix
Expand All @@ -68,29 +71,38 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
*/
uint16_t get_service() const
{
return static_cast<uint16_t>(state_interfaces_[1].get().get_value());
return static_cast<uint16_t>(state_interfaces_[1].get().template get_value<double>().value());
}

/**
* Return latitude reported by a GPS
*
* \return Latitude.
*/
double get_latitude() const { return state_interfaces_[2].get().get_value(); }
double get_latitude() const
{
return state_interfaces_[2].get().template get_value<double>().value();
}

/**
* Return longitude reported by a GPS
*
* \return Longitude.
*/
double get_longitude() const { return state_interfaces_[3].get().get_value(); }
double get_longitude() const
{
return state_interfaces_[3].get().template get_value<double>().value();
}

/**
* Return altitude reported by a GPS
*
* \return Altitude.
*/
double get_altitude() const { return state_interfaces_[4].get().get_value(); }
double get_altitude() const
{
return state_interfaces_[4].get().template get_value<double>().value();
}

/**
* Return covariance reported by a GPS.
Expand All @@ -102,9 +114,9 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
const std::array<double, 9> & get_covariance()
{
covariance_[0] = state_interfaces_[5].get().get_value();
covariance_[4] = state_interfaces_[6].get().get_value();
covariance_[8] = state_interfaces_[7].get().get_value();
covariance_[0] = state_interfaces_[5].get().template get_value<double>().value();
covariance_[4] = state_interfaces_[6].get().template get_value<double>().value();
covariance_[8] = state_interfaces_[7].get().template get_value<double>().value();
return covariance_;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
std::array<double, 4> orientation;
for (auto i = 0u; i < orientation.size(); ++i)
{
orientation[i] = state_interfaces_[i].get().get_value();
orientation[i] = state_interfaces_[i].get().get_value<double>().value();
}
return orientation;
}
Expand All @@ -69,7 +69,8 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
const std::size_t interface_offset{4};
for (auto i = 0u; i < angular_velocity.size(); ++i)
{
angular_velocity[i] = state_interfaces_[interface_offset + i].get().get_value();
angular_velocity[i] =
state_interfaces_[interface_offset + i].get().get_value<double>().value();
}
return angular_velocity;
}
Expand All @@ -86,7 +87,8 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
const std::size_t interface_offset{7};
for (auto i = 0u; i < linear_acceleration.size(); ++i)
{
linear_acceleration[i] = state_interfaces_[interface_offset + i].get().get_value();
linear_acceleration[i] =
state_interfaces_[interface_offset + i].get().get_value<double>().value();
}
return linear_acceleration;
}
Expand Down
Loading

0 comments on commit 0aa3494

Please sign in to comment.