Skip to content

Commit cd5557b

Browse files
committed
fix build under ros2 jazzy
1 parent 430a084 commit cd5557b

File tree

18 files changed

+86
-18
lines changed

18 files changed

+86
-18
lines changed

.github/workflows/ros-jazzy.yml

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
name: jazzy
2+
3+
on:
4+
push:
5+
branches: [ "master" ]
6+
pull_request:
7+
branches: [ "master" ]
8+
9+
jobs:
10+
build:
11+
runs-on: ubuntu-24.04
12+
container:
13+
image: ros:jazzy
14+
steps:
15+
- uses: actions/checkout@v4
16+
with:
17+
submodules: recursive
18+
- name: Ignore scara_moveit
19+
run: touch decomposition/scara_moveit/AMENT_IGNORE
20+
- name: Install dependencies
21+
shell: bash
22+
run: |
23+
sudo apt update
24+
rosdep update
25+
rosdep install -y --rosdistro jazzy --from-paths . --ignore-src
26+
source /opt/ros/jazzy/local_setup.bash
27+
colcon build --packages-skip-regex '.*'
28+
- name: Install Eigen3
29+
run: |
30+
sudo apt install -y libeigen3-dev
31+
- name: Build workspace
32+
uses: ichiro-its/ros2-ws-action/[email protected]

decomposition/meta_chassis_controller/include/meta_chassis_controller/agv_chassis_controller.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,11 @@ class AgvChassisController : public controller_interface::ChainableControllerInt
4949
controller_interface::CallbackReturn
5050
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
5151

52+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
53+
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period) override;
54+
#else
5255
controller_interface::return_type update_reference_from_subscribers() override;
56+
#endif
5357

5458
controller_interface::return_type
5559
update_and_write_commands(const rclcpp::Time &time,

decomposition/meta_chassis_controller/include/meta_chassis_controller/omni_chassis_controller.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,11 @@ class OmniChassisController : public controller_interface::ChainableControllerIn
4848
controller_interface::CallbackReturn
4949
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
5050

51+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
52+
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period) override;
53+
#else
5154
controller_interface::return_type update_reference_from_subscribers() override;
55+
#endif
5256

5357
controller_interface::return_type
5458
update_and_write_commands(const rclcpp::Time &time,

decomposition/meta_chassis_controller/src/agv_chassis_controller.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -258,8 +258,11 @@ AgvChassisController::on_deactivate(const rclcpp_lifecycle::State & /*previous_s
258258
return controller_interface::CallbackReturn::SUCCESS;
259259
}
260260

261-
controller_interface::return_type
262-
AgvChassisController::update_reference_from_subscribers() {
261+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
262+
controller_interface::return_type AgvChassisController::update_reference_from_subscribers(const rclcpp::Time &time,const rclcpp::Duration &period){
263+
#else
264+
controller_interface::return_type AgvChassisController::update_reference_from_subscribers(){
265+
#endif
263266
auto cur_ref = *(ref_buf_.readFromRT());
264267

265268
if (const auto command_age = get_node()->now() - cur_ref->header.stamp;

decomposition/meta_chassis_controller/src/omni_chassis_controller.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -206,8 +206,11 @@ OmniChassisController::on_deactivate(const rclcpp_lifecycle::State & /*previous_
206206
return controller_interface::CallbackReturn::SUCCESS;
207207
}
208208

209-
controller_interface::return_type
210-
OmniChassisController::update_reference_from_subscribers() {
209+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
210+
controller_interface::return_type OmniChassisController::update_reference_from_subscribers(const rclcpp::Time &time,const rclcpp::Duration &period){
211+
#else
212+
controller_interface::return_type OmniChassisController::update_reference_from_subscribers(){
213+
#endif
211214
auto cur_ref = *(ref_buf_.readFromRT());
212215

213216
if (const auto command_age = get_node()->now() - cur_ref->header.stamp;

decomposition/meta_gimbal_controller/include/gimbal_controller/gimbal_controller.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,11 @@ class GimbalController : public controller_interface::ChainableControllerInterfa
4949
controller_interface::CallbackReturn
5050
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
5151

52+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
53+
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period) override;
54+
#else
5255
controller_interface::return_type update_reference_from_subscribers() override;
56+
#endif
5357

5458
controller_interface::return_type
5559
update_and_write_commands(const rclcpp::Time &time,

decomposition/meta_gimbal_controller/include/gimbal_controller/gimbal_position_controller.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,11 @@ class GimbalPositionController : public controller_interface::ChainableControlle
5050
controller_interface::CallbackReturn
5151
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
5252

53+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
54+
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period) override;
55+
#else
5356
controller_interface::return_type update_reference_from_subscribers() override;
57+
#endif
5458

5559
controller_interface::return_type
5660
update_and_write_commands(const rclcpp::Time &time,

decomposition/meta_gimbal_controller/src/gimbal_controller.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
#include <string>
77
#include <tf2/LinearMath/Quaternion.h>
88
#include <tf2/LinearMath/Matrix3x3.h>
9-
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
9+
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1010
#include <vector>
1111

1212
#include "angles/angles.h"
@@ -214,8 +214,11 @@ controller_interface::CallbackReturn
214214
GimbalController::on_deactivate(const rclcpp_lifecycle::State & /*previous_state*/) {
215215
return controller_interface::CallbackReturn::SUCCESS;
216216
}
217-
218-
controller_interface::return_type GimbalController::update_reference_from_subscribers() {
217+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
218+
controller_interface::return_type GimbalController::update_reference_from_subscribers(const rclcpp::Time &time,const rclcpp::Duration &period){
219+
#else
220+
controller_interface::return_type GimbalController::update_reference_from_subscribers(){
221+
#endif
219222
auto current_ref = *(input_ref_.readFromRT()); // A shared_ptr must be allocated
220223
// immediately to prevent dangling
221224

decomposition/meta_gimbal_controller/src/gimbal_position_controller.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
#include <string>
77
#include <tf2/LinearMath/Matrix3x3.h>
88
#include <tf2/LinearMath/Quaternion.h>
9-
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
9+
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1010
#include <vector>
1111

1212
#include "angles/angles.h"
@@ -213,8 +213,11 @@ namespace gimbal_controller
213213
return controller_interface::CallbackReturn::SUCCESS;
214214
}
215215

216-
controller_interface::return_type GimbalPositionController::update_reference_from_subscribers()
217-
{
216+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
217+
controller_interface::return_type GimbalPositionController::update_reference_from_subscribers(const rclcpp::Time &time,const rclcpp::Duration &period){
218+
#else
219+
controller_interface::return_type GimbalPositionController::update_reference_from_subscribers(){
220+
#endif
218221
auto current_ref = *(input_ref_.readFromRT()); // A shared_ptr must be allocated
219222
// immediately to prevent dangling
220223

decomposition/meta_shoot_controller/include/shoot_controller/shoot_controller.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,11 @@ namespace shoot_controller {
4646

4747
controller_interface::CallbackReturn
4848
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
49-
49+
#if RCLCPP_VERSION_MAJOR >= 28 // ROS 2 Jazzy or later
50+
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period) override;
51+
#else
5052
controller_interface::return_type update_reference_from_subscribers() override;
53+
#endif
5154

5255
controller_interface::return_type
5356
update_and_write_commands(const rclcpp::Time &time,

0 commit comments

Comments
 (0)