Skip to content

Commit

Permalink
Merge branch 'master' into async_controllers
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Oct 17, 2024
2 parents e38f567 + 83fff77 commit cbc3638
Show file tree
Hide file tree
Showing 68 changed files with 2,308 additions and 215 deletions.
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ repos:

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.8
rev: v19.1.0
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down Expand Up @@ -109,7 +109,7 @@ repos:

# Docs - RestructuredText hooks
- repo: https://github.com/PyCQA/doc8
rev: v1.1.1
rev: v1.1.2
hooks:
- id: doc8
args: ['--max-line-length=100', '--ignore=D001']
Expand All @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

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

4.18.0 (2024-10-07)
-------------------
* Adapt controller Reference/StateInterfaces to New Way of Exporting (variant support) (`#1689 <https://github.com/ros-controls/ros2_control/issues/1689>`_)
* [ControllerInterface] Fix to properly propagate the controller NodeOptions (`#1762 <https://github.com/ros-controls/ros2_control/issues/1762>`_)
* [Controller Interface] Make assign and release interfaces virtual (`#1743 <https://github.com/ros-controls/ros2_control/issues/1743>`_)
* Contributors: Manuel Muth, Sai Kishor Kothakota

4.17.0 (2024-09-11)
-------------------
* Rename `get_state` and `set_state` Functions to `get/set_lifecylce_state` (variant support) (`#1683 <https://github.com/ros-controls/ros2_control/issues/1683>`_)
Expand Down
10 changes: 10 additions & 0 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ target_compile_definitions(controller_interface PRIVATE "CONTROLLER_INTERFACE_BU

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)

ament_add_gmock(test_controller_interface test/test_controller_interface.cpp)
Expand Down Expand Up @@ -75,6 +76,15 @@ if(BUILD_TESTING)
ament_target_dependencies(test_imu_sensor
sensor_msgs
)

ament_add_gmock(test_pose_sensor test/test_pose_sensor.cpp)
target_link_libraries(test_pose_sensor
controller_interface
hardware_interface::hardware_interface
)
ament_target_dependencies(test_pose_sensor
geometry_msgs
)
endif()

install(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,9 @@
#ifndef CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_

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

#include "controller_interface/controller_interface_base.hpp"
Expand Down Expand Up @@ -57,10 +59,10 @@ class ChainableControllerInterface : public ControllerInterfaceBase
bool is_chainable() const final;

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

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

CONTROLLER_INTERFACE_PUBLIC
bool set_chained_mode(bool chained_mode) final;
Expand Down Expand Up @@ -131,11 +133,22 @@ class ChainableControllerInterface : public ControllerInterfaceBase

/// Storage of values for state interfaces
std::vector<std::string> exported_state_interface_names_;
std::vector<hardware_interface::StateInterface::SharedPtr> ordered_exported_state_interfaces_;
std::unordered_map<std::string, hardware_interface::StateInterface::SharedPtr>
exported_state_interfaces_;
// BEGIN (Handle export change): for backward compatibility
std::vector<double> state_interfaces_values_;
// END

/// Storage of values for reference interfaces
std::vector<std::string> exported_reference_interface_names_;
// BEGIN (Handle export change): for backward compatibility
std::vector<double> reference_interfaces_;
// END
std::vector<hardware_interface::CommandInterface::SharedPtr>
ordered_exported_reference_interfaces_;
std::unordered_map<std::string, hardware_interface::CommandInterface::SharedPtr>
exported_reference_interfaces_;

private:
/// A flag marking if a chainable controller is currently preceded by another controller.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,15 +47,15 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase
* \returns empty list.
*/
CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface> export_state_interfaces() final;
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> export_reference_interfaces() final;
std::vector<hardware_interface::CommandInterface::SharedPtr> export_reference_interfaces() final;

/**
* Controller is not chainable, therefore no chained mode can be set.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -252,7 +252,8 @@ 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> export_reference_interfaces() = 0;
virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
export_reference_interfaces() = 0;

/**
* Export interfaces for a chainable controller that can be used as state interface by other
Expand All @@ -261,7 +262,8 @@ 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> export_state_interfaces() = 0;
virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
export_state_interfaces() = 0;

/**
* Set chained mode of a chainable controller. This method triggers internal processes to switch
Expand Down
10 changes: 10 additions & 0 deletions controller_interface/include/controller_interface/helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,16 @@ inline bool interface_list_contains_interface_type(
interface_type_list.end();
}

template <typename T>
void add_element_to_list(std::vector<T> & list, const T & element)
{
if (std::find(list.begin(), list.end(), element) == list.end())
{
// Only add to the list if it doesn't exist
list.push_back(element);
}
}

} // namespace controller_interface

#endif // CONTROLLER_INTERFACE__HELPERS_HPP_
110 changes: 110 additions & 0 deletions controller_interface/include/semantic_components/pose_sensor.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
// Copyright 2024 FZI Forschungszentrum Informatik
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_

#include <array>
#include <limits>
#include <string>

#include "geometry_msgs/msg/pose.hpp"
#include "semantic_components/semantic_component_interface.hpp"

namespace semantic_components
{

class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
{
public:
/// Constructor for a standard pose sensor with interface names set based on sensor name.
explicit PoseSensor(const std::string & name) : SemanticComponentInterface{name, 7}
{
// Use standard interface names
interface_names_.emplace_back(name_ + '/' + "position.x");
interface_names_.emplace_back(name_ + '/' + "position.y");
interface_names_.emplace_back(name_ + '/' + "position.z");
interface_names_.emplace_back(name_ + '/' + "orientation.x");
interface_names_.emplace_back(name_ + '/' + "orientation.y");
interface_names_.emplace_back(name_ + '/' + "orientation.z");
interface_names_.emplace_back(name_ + '/' + "orientation.w");

// Set all sensor values to default value NaN
std::fill(position_.begin(), position_.end(), std::numeric_limits<double>::quiet_NaN());
std::fill(orientation_.begin(), orientation_.end(), std::numeric_limits<double>::quiet_NaN());
}

virtual ~PoseSensor() = default;

/// Update and return position.
/*!
* Update and return current pose position from state interfaces.
*
* \return Array of position coordinates.
*/
std::array<double, 3> get_position()
{
for (size_t i = 0; i < 3; ++i)
{
position_[i] = state_interfaces_[i].get().get_value();
}

return position_;
}

/// Update and return orientation
/*!
* Update and return current pose orientation from state interfaces.
*
* \return Array of orientation coordinates in xyzw convention.
*/
std::array<double, 4> get_orientation()
{
for (size_t i = 3; i < 7; ++i)
{
orientation_[i - 3] = state_interfaces_[i].get().get_value();
}

return orientation_;
}

/// Fill pose message with current values.
/**
* Fill a pose message with current position and orientation from the state interfaces.
*/
bool get_values_as_message(geometry_msgs::msg::Pose & message)
{
// Update state from state interfaces
get_position();
get_orientation();

// Set message values from current state
message.position.x = position_[0];
message.position.y = position_[1];
message.position.z = position_[2];
message.orientation.x = orientation_[0];
message.orientation.y = orientation_[1];
message.orientation.z = orientation_[2];
message.orientation.w = orientation_[3];

return true;
}

protected:
std::array<double, 3> position_;
std::array<double, 4> orientation_;
};

} // namespace semantic_components

#endif // SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
3 changes: 2 additions & 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.17.0</version>
<version>4.18.0</version>
<description>Description of controller_interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand All @@ -23,6 +23,7 @@
<exec_depend>realtime_tools</exec_depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>geometry_msgs</test_depend>
<test_depend>sensor_msgs</test_depend>

<export>
Expand Down
Loading

0 comments on commit cbc3638

Please sign in to comment.