Skip to content

Commit

Permalink
Merge branch 'humble' into mergify/bp/humble/pr-1046
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Nov 10, 2023
2 parents f2ac6d7 + b9cdcfe commit 3773340
Show file tree
Hide file tree
Showing 58 changed files with 2,947 additions and 288 deletions.
4 changes: 2 additions & 2 deletions .docker/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
Meant to provide basic docker containers for CI or development purposes. To use them, make sure you have [Docker](https://docs.docker.com/get-docker/) installed. You then can pull the latest source or build image or build any version and run the image by following tag specific commands as described below:

## Source folder and tag
Downloads and builds ros2_controls into a workspace for development use exactly as is found [here](https://ros-controls.github.io/control.ros.org/getting_started.html#compiling). This is primarily used for development and CI of ros2_control and related packages.
Downloads and builds ros2_controls into a workspace for development use exactly as is found [here](https://control.ros.org/master/doc/getting_started/getting_started.html#building-from-source). This is primarily used for development and CI of ros2_control and related packages.

You can pull a prebuilt image with this docker tag: `ghcr.io/ros-controls/ros2_control_source`.

Expand All @@ -30,7 +30,7 @@ docker run -it --mount type=volume,source=name-of-volume,destination=/root/ws_ro
Note: this is probably the preferred solution as changes persist across rebuilds of container and doesn't require you to pull all repositories that you want to edit as they'll already be in the container.

## Release folder and tag
Installs ros2_control in the base ros2 docker container as mentioned [here](https://ros-controls.github.io/control.ros.org/getting_started.html#getting-started). This is mainly intended for development of external packages that rely on ros2_control.
Installs ros2_control in the base ros2 docker container as mentioned [here](https://control.ros.org/master/doc/getting_started/getting_started.html#building-from-source). This is mainly intended for development of external packages that rely on ros2_control.

You can pull a prebuilt image using the following tag: `ghcr.io/ros2-controls/ros2_control_release`.

Expand Down
6 changes: 3 additions & 3 deletions .github/ISSUE_TEMPLATE/good-first-issue.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ Nothing. This issue is meant to welcome you to Open Source :) We are happy to wa

- [ ] 🙋 **Claim this issue**: Comment below. If someone else has claimed it, ask if they've opened a pull request already and if they're stuck -- maybe you can help them solve a problem or move it along!

- [ ] 🗄️ **Create a local workspace** for making your changes and testing [following these instructions](https://docs.ros.org/en/galactic/Tutorials/Workspace/Creating-A-Workspace.html), for Step3 use "Download Source Code" section with [these instructions](https://ros-controls.github.io/control.ros.org/getting_started.html#compiling).
- [ ] 🗄️ **Create a local workspace** for making your changes and testing [following these instructions](https://docs.ros.org/en/humble/Tutorials/Workspace/Creating-A-Workspace.html), for Step 3 use "Download Source Code" section with [these instructions](https://control.ros.org/humble/doc/getting_started/getting_started.html#building-from-source).

- [ ] 🍴 **Fork the repository** using the handy button at the top of the repository page and **clone** it into `~/ws_ros2_control/src/ros-controls/ros2_control`, [here is a guide that you can follow](https://guides.github.com/activities/forking/) (You will have to remove or empty the existing `ros2_control` folder before cloning your own fork)

Expand All @@ -53,8 +53,8 @@ Nothing. This issue is meant to welcome you to Open Source :) We are happy to wa

Don’t hesitate to ask questions or to get help if you feel like you are getting stuck. For example leave a comment below!
Furthermore, you find helpful resources here:
* [ROS2 Control Contribution Guide](https://ros-controls.github.io/control.ros.org/contributing.html)
* [ROS2 Tutorials](https://docs.ros.org/en/galactic/Tutorials.html)
* [ros2_control Contribution Guide](https://control.ros.org/humble/doc/contributing/contributing.html)
* [ROS2 Tutorials](https://docs.ros.org/en/humble/Tutorials.html)
* [ROS Answers](https://answers.ros.org/questions/)

**Good luck with your first issue!**
2 changes: 1 addition & 1 deletion CONTRIBUTING.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ Please try to include as much information as you can. Details like these are inc


## Contributing via Pull Requests
The following guidance should be up-to-date, but the documentation as found [here](https://ros-controls.github.io/control.ros.org/contributing.html#pull-requests) should prove as the final say.
The following guidance should be up-to-date, but the documentation as found [here](https://control.ros.org/master/doc/contributing/contributing.html#pull-requests) should prove as the final say.

Contributions via pull requests are much appreciated.
Before sending us a pull request, please ensure that:
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
[![Licence](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0)

This package is a part of the ros2_control framework.
For more, please check the [documentation](https://ros-controls.github.io/control.ros.org/).
For more, please check the [documentation](https://control.ros.org/).


## Build status
Expand Down
23 changes: 23 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,29 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.34.0 (2023-11-08)
-------------------

2.33.0 (2023-10-11)
-------------------

2.32.0 (2023-10-03)
-------------------

2.31.0 (2023-09-11)
-------------------
* add a broadcaster for range sensor (`#1091 <https://github.com/ros-controls/ros2_control/issues/1091>`_) (`#1100 <https://github.com/ros-controls/ros2_control/issues/1100>`_)
* Contributors: flochre

2.30.0 (2023-08-14)
-------------------

2.29.0 (2023-07-09)
-------------------

2.28.0 (2023-06-23)
-------------------

2.27.0 (2023-06-14)
-------------------
* [Humble] enable ReflowComments to also use ColumnLimit on comments (`#1038 <https://github.com/ros-controls/ros2_control/issues/1038>`_)
Expand Down
60 changes: 60 additions & 0 deletions controller_interface/include/semantic_components/range_sensor.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
// Copyright 2023 flochre
//
// 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__RANGE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_

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

#include "semantic_components/semantic_component_interface.hpp"
#include "sensor_msgs/msg/range.hpp"

namespace semantic_components
{
class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
{
public:
explicit RangeSensor(const std::string & name) : SemanticComponentInterface(name, 1)
{
interface_names_.emplace_back(name_ + "/" + "range");
}

virtual ~RangeSensor() = default;

/**
* Return Range reported by a sensor
*
* \return value of the range in meters
*/
float get_range() { return state_interfaces_[0].get().get_value(); }

/// Return Range message with range in meters
/**
* Constructs and return a Range message from the current values.
* \return Range message from values;
*/
bool get_values_as_message(sensor_msgs::msg::Range & message)
{
// update the message values
message.range = get_range();

return true;
}
};

} // namespace semantic_components

#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
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>2.27.0</version>
<version>2.34.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
37 changes: 37 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,43 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.34.0 (2023-11-08)
-------------------
* [Humble] Controller sorting (`#1157 <https://github.com/ros-controls/ros2_control/issues/1157>`_)
* Update spawner to accept controllers list and start them in sequence (backport `#1139 <https://github.com/ros-controls/ros2_control/issues/1139>`_) (`#1149 <https://github.com/ros-controls/ros2_control/issues/1149>`_)
* Create doc file for chained controllers (backport `#985 <https://github.com/ros-controls/ros2_control/issues/985>`_) (`#1131 <https://github.com/ros-controls/ros2_control/issues/1131>`_)
* Contributors: Sai Kishor Kothakota, mergify[bot]

2.33.0 (2023-10-11)
-------------------
* Export of the get_cm_node_options() from robostack (`#1129 <https://github.com/ros-controls/ros2_control/issues/1129>`_) (`#1130 <https://github.com/ros-controls/ros2_control/issues/1130>`_)
* Contributors: mergify[bot]

2.32.0 (2023-10-03)
-------------------
* Fix multiple calls to export reference interfaces (backport `#1108 <https://github.com/ros-controls/ros2_control/issues/1108>`_) (`#1114 <https://github.com/ros-controls/ros2_control/issues/1114>`_)
* Contributors: Sai Kishor Kothakota, Dr Denis

2.31.0 (2023-09-11)
-------------------
* [Docs] Fix information about activation and deactivation of chainable controllers (`#1104 <https://github.com/ros-controls/ros2_control/issues/1104>`_) (`#1106 <https://github.com/ros-controls/ros2_control/issues/1106>`_)
* Contributors: mergify[bot]

2.30.0 (2023-08-14)
-------------------
* [CM] Fixes the issue with individual controller's update rate (`#1082 <https://github.com/ros-controls/ros2_control/issues/1082>`_) (`#1097 <https://github.com/ros-controls/ros2_control/issues/1097>`_)
* Contributors: Sai Kishor Kothakota

2.29.0 (2023-07-09)
-------------------
* [CM] Make error message after trying to active controller more informative. (`#1066 <https://github.com/ros-controls/ros2_control/issues/1066>`_) (`#1072 <https://github.com/ros-controls/ros2_control/issues/1072>`_)
* added controller manager runner to have update cycles (`#1075 <https://github.com/ros-controls/ros2_control/issues/1075>`_) (`#1076 <https://github.com/ros-controls/ros2_control/issues/1076>`_)
* Fix equal and higher controller update rate (backport `#1070 <https://github.com/ros-controls/ros2_control/issues/1070>`_) (`#1071 <https://github.com/ros-controls/ros2_control/issues/1071>`_)
* Contributors: Sai Kishor Kothakota, Dr Denis

2.28.0 (2023-06-23)
-------------------

2.27.0 (2023-06-14)
-------------------
* Docs: Use branch name substitution for all links (backport `#1031 <https://github.com/ros-controls/ros2_control/issues/1031>`_) (`#1042 <https://github.com/ros-controls/ros2_control/issues/1042>`_)
Expand Down
12 changes: 12 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
pluginlib
rclcpp
realtime_tools
std_msgs
)

find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -133,6 +134,17 @@ if(BUILD_TESTING)
controller_manager_msgs
ros2_control_test_assets
)
ament_add_gmock(test_controller_manager_urdf_passing
test/test_controller_manager_urdf_passing.cpp
)
target_include_directories(test_controller_manager_urdf_passing PRIVATE include)
target_link_libraries(test_controller_manager_urdf_passing
controller_manager
)
ament_target_dependencies(test_controller_manager_urdf_passing
controller_manager_msgs
ros2_control_test_assets
)

add_library(test_controller_with_interfaces SHARED test/test_controller_with_interfaces/test_controller_with_interfaces.cpp)
target_include_directories(test_controller_with_interfaces PRIVATE include)
Expand Down
Loading

0 comments on commit 3773340

Please sign in to comment.