Skip to content

Commit 154ccc9

Browse files
JanNiklasFeldtexhnolyze
authored andcommitted
Changes according to make format and changed ros distro to jazzy
1 parent 7179449 commit 154ccc9

File tree

66 files changed

+125
-153
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

66 files changed

+125
-153
lines changed

.github/workflows/ci.yml

+2-2
Original file line numberDiff line numberDiff line change
@@ -39,14 +39,14 @@ jobs:
3939
4040
- name: Build packages
4141
run: |
42-
. /opt/ros/iron/setup.sh
42+
. /opt/ros/jazzy/setup.sh
4343
colcon build --symlink-install
4444
working-directory: /colcon_ws
4545

4646
- name: Test packages
4747
run: |
4848
# Source workspace
49-
. /opt/ros/iron/setup.sh
49+
. /opt/ros/jazzy/setup.sh
5050
. install/setup.sh
5151
# Run tests for all packages
5252
colcon test --event-handlers console_direct+ --return-code-on-test-failure --parallel-workers 1

.pre-commit-config.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ repos:
1616
- id: cppcheck
1717
args:
1818
- "--inline-suppr"
19-
- "--suppress=missingInclude"
19+
- "--suppress=missingIncludeSystem"
2020
- "--suppress=unmatchedSuppression"
2121
- "--suppress=unusedFunction"
2222
- "--suppress=unusedStructMember"

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
[![Build & Test](https://github.com/bit-bots/bitbots_main/actions/workflows/ci.yml/badge.svg)](https://github.com/bit-bots/bitbots_main/actions/workflows/ci.yml)
44
[![Code style checks](https://github.com/bit-bots/bitbots_main/actions/workflows/pre-commit.yml/badge.svg)](https://github.com/bit-bots/bitbots_main/actions/workflows/pre-commit.yml)
5-
[![ROS Version Iron](https://img.shields.io/badge/ROS%20Version-Iron-ab8c71)](https://docs.ros.org/en/iron/index.html)
5+
[![ROS Version Jazzy](https://img.shields.io/badge/ROS%20Version-Jazzy-00b8ff)](https://docs.ros.org/en/jazzy/index.html)
66

77
This git repository contains all RoboCup-related code and documentation from the Hamburg Bit-Bots team.
88
All code is written as individual ROS 2 packages targeting Ubuntu.

bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
#ifndef BITBOTS_ROS_CONTROL_INCLUDE_BITBOTS_ROS_CONTROL_UTILS_H_
22
#define BITBOTS_ROS_CONTROL_INCLUDE_BITBOTS_ROS_CONTROL_UTILS_H_
33

4-
#include "bitbots_msgs/msg/audio.hpp"
5-
#include "rclcpp/rclcpp.hpp"
4+
#include <bitbots_msgs/msg/audio.hpp>
5+
#include <rclcpp/rclcpp.hpp>
66

77
namespace bitbots_ros_control {
88

@@ -13,7 +13,7 @@ void speakError(rclcpp::Publisher<bitbots_msgs::msg::Audio>::SharedPtr speak_pub
1313

1414
uint16_t dxlMakeword(uint64_t a, uint64_t b);
1515
uint32_t dxlMakedword(uint64_t a, uint64_t b);
16-
float dxlMakeFloat(uint8_t* data);
16+
float dxlMakeFloat(const uint8_t* data);
1717

1818
std::string gyroRangeToString(uint8_t range);
1919
std::string accelRangeToString(uint8_t range);

bitbots_lowlevel/bitbots_ros_control/src/dynamixel_servo_hardware_interface.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ void DynamixelServoHardwareInterface::individualTorqueCb(bitbots_msgs::msg::Join
148148
RCLCPP_WARN(nh_->get_logger(), "Couldn't set torque for servo %s ", msg.joint_names[i].c_str());
149149
}
150150
}
151-
for (auto &bus : bus_interfaces_) {
151+
for (const auto &bus : bus_interfaces_) {
152152
bus->switch_individual_torque_ = true;
153153
}
154154
}
@@ -157,7 +157,7 @@ void DynamixelServoHardwareInterface::setTorqueCb(std_msgs::msg::Bool::SharedPtr
157157
/**
158158
* This saves the given required value, so that it can be written to the servos in the write method
159159
*/
160-
for (auto &bus : bus_interfaces_) {
160+
for (const auto &bus : bus_interfaces_) {
161161
bus->goal_torque_ = enabled->data;
162162
}
163163
for (size_t j = 0; j < joint_names_.size(); j++) {
@@ -196,7 +196,7 @@ void DynamixelServoHardwareInterface::write(const rclcpp::Time &t, const rclcpp:
196196
// set all values from controller to the buses
197197
// todo improve performance
198198
int i = 0;
199-
for (auto &bus : bus_interfaces_) {
199+
for (const auto &bus : bus_interfaces_) {
200200
for (int j = 0; j < bus->joint_count_; j++) {
201201
bus->goal_position_[j] = goal_position_[i];
202202
bus->goal_velocity_[j] = goal_velocity_[i];

bitbots_lowlevel/bitbots_ros_control/src/servo_bus_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,7 @@ bool ServoBusInterface::writeROMRAM(bool first_time) {
202202
// Allocate memory for the values in the driver
203203
std::vector<int> values(joint_names_.size());
204204
// Iterate over parameter names
205-
for (auto register_name : parameter_names) {
205+
for (const auto &register_name : parameter_names) {
206206
// Get the value for each joint
207207
for (size_t num = 0; num < joint_names_.size(); num++) {
208208
// Get the value from the cache

bitbots_lowlevel/bitbots_ros_control/src/utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ uint32_t dxlMakedword(uint64_t a, uint64_t b) {
4040
return uint32_t(uint16_t(a & 0xffff) | uint32_t(uint16_t(b & 0xffff) << 16));
4141
}
4242

43-
float dxlMakeFloat(uint8_t* data) {
43+
float dxlMakeFloat(const uint8_t* data) {
4444
float f;
4545
uint32_t b = dxlMakedword(dxlMakeword(data[0], data[1]), dxlMakeword(data[2], data[3]));
4646
memcpy(&f, &b, sizeof(f));

bitbots_lowlevel/bitbots_ros_control/src/wolfgang_hardware_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -307,7 +307,7 @@ void WolfgangHardwareInterface::write(const rclcpp::Time &t, const rclcpp::Durat
307307
}
308308
if (!bus_start_time_ || t > bus_start_time_.value()) {
309309
if (bus_first_write_) {
310-
for (std::vector<std::shared_ptr<HardwareInterface>> &port_interfaces : interfaces_) {
310+
for (std::vector<std::shared_ptr<HardwareInterface>> const &port_interfaces : interfaces_) {
311311
for (std::shared_ptr<HardwareInterface> interface : port_interfaces) {
312312
interface->restoreAfterPowerCycle();
313313
}

bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,13 @@
1212
#include <iostream>
1313
#include <memory>
1414
#include <opencv2/imgproc/imgproc.hpp>
15+
#include <pylon_camera_parameters.hpp>
1516
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
1617
#include <rclcpp/logger.hpp>
1718
#include <rclcpp/rclcpp.hpp>
1819
#include <string>
1920
#include <vector>
2021

21-
#include "pylon_camera_parameters.hpp"
22-
2322
using std::placeholders::_1, std::placeholders::_2;
2423
using namespace Pylon;
2524

@@ -271,7 +270,8 @@ class BaslerCamera {
271270
}
272271

273272
// Convert to cv::Mat
274-
cv::Mat image(ptrGrabResult->GetHeight(), ptrGrabResult->GetWidth(), CV_8UC1, (uint8_t*)ptrGrabResult->GetBuffer());
273+
cv::Mat image(ptrGrabResult->GetHeight(), ptrGrabResult->GetWidth(), CV_8UC1,
274+
static_cast<uint8_t*>(ptrGrabResult->GetBuffer()));
275275

276276
// Create cv::Mat for color image
277277
cv::Mat color(image.size(), CV_MAKETYPE(CV_8U, 3));

bitbots_misc/bitbots_docs/docs/manual/testing/testing.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ Compile (compiles)
4949
------------------
5050

5151
The first step is to test if the package compiles.
52-
Obviously this should preferably be tested on the same system that is used on the robot (Ubuntu 22.04 with the iron distribution).
52+
Obviously this should preferably be tested on the same system that is used on the robot (Ubuntu 24.04 with the jazzy distribution).
5353
A part of this is to check if all dependencies are correct in the package.xml.
5454
This is important so they can be installed with rosdep.
5555

bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ For compilation of the whole meta repository run ``cba``, which is an alias for:
3535
``cd $COLCON_WS; colcon build --symlink-install --continue-on-error``
3636
After a successful run, before we are able to use any ros commands we now need to source colcon built sources
3737
with ``sa``, which is an alias for:
38-
``source "/opt/ros/iron/setup.$SHELL" && source "$COLCON_WS/install/setup.$SHELL"``
38+
``source "/opt/ros/jazzy/setup.$SHELL" && source "$COLCON_WS/install/setup.$SHELL"``
3939

4040
**3. Run Webots Simulation**
4141

bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst

+7-7
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
11
Software installation with ROS2
22
===============================
33

4-
In this tutorial, we will learn how to install ROS2 Iron Irwini on Ubuntu 22.04 and build our software stack.
4+
In this tutorial, we will learn how to install ROS2 Jazzy Jalisco on Ubuntu 24.04 and build our software stack.
55

66
**TLDR**: single command setup
77
------------------------------
88

99
**Prerequirements**
10-
- You have a running Ubuntu 22.04 environment
10+
- You have a running Ubuntu 24.04 environment
1111
- You have an existing Github account and added a SSH key to your account
1212
- You have root access to your system (sudo)
1313

@@ -23,17 +23,17 @@ If you have not previously set up any of our software stack, you can use the fol
2323
Manual steps with in depth explanation
2424
--------------------------------------
2525

26-
**0. Use Ubuntu 22.04**
26+
**0. Use Ubuntu 24.04**
2727

2828
As ROS works best on Ubuntu, we are using this distribution.
29-
Currently, ROS2 Iron runs on Ubuntu 22.04.
29+
Currently, ROS2 Jazzy runs on Ubuntu 24.04.
3030

31-
If you are not already using Ubuntu 22.04, consider installing it on your system (perhaps as a dual boot?).
31+
If you are not already using Ubuntu 24.04, consider installing it on your system (perhaps as a dual boot?).
3232
Alternatively you can use a devcontainer :doc:`vscode-dev-container`, with a preconfigured environment and follow those instructions, as these docs do not apply to the devcontainer.
3333

3434
**1. Setup and Install ROS 2**
3535

36-
- Follow this guide and when it comes to the section **Install ROS 2 packages**, install the recommended ``ros-iron-desktop-full``: https://docs.ros.org/en/iron/Installation/Ubuntu-Install-Debians.html
36+
- Follow this guide and when it comes to the section **Install ROS 2 packages**, install the recommended ``ros-jazzy-desktop-full``: https://docs.ros.org/en/jazzy/Installation/Ubuntu-Install-Debs.html
3737
- Install additional dependencies:
3838

3939
.. code-block:: bash
@@ -88,7 +88,7 @@ If you want to install it, you can do so by running ``make webots`` in the bitbo
8888

8989
**4. Setup colcon workspace**
9090

91-
`Colcon <https://docs.ros.org/en/iron/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html>`_ is the tool provided by ROS 2 to build and install our ROS packages, so that they can be launched later.
91+
`Colcon <https://docs.ros.org/en/jazzy/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html>`_ is the tool provided by ROS 2 to build and install our ROS packages, so that they can be launched later.
9292
The colcon workspace is where your source code gets build and where we use colcon.
9393

9494
- Create colcon workspace directory (typically ``~/colcon_ws/``)

bitbots_misc/bitbots_docs/docs/manual/tutorials/vscode-ros2.rst

+2-2
Original file line numberDiff line numberDiff line change
@@ -9,14 +9,14 @@ Navigate to your colcon workspace.
99

1010
Source ros
1111

12-
`source /opt/ros/iron/setup.zsh`
12+
`source /opt/ros/jazzy/setup.zsh`
1313

1414
Open VSCode
1515

1616
`code .`
1717

1818
Install the ROS extension (from Microsoft).
19-
You should see a `ROS2.iron` in the lower left corner.
19+
You should see a `ROS2.jazzy` in the lower left corner.
2020

2121
Now you should be able to build the code with `Ctrl+Shift+B`
2222

bitbots_misc/bitbots_tf_buffer/src/bitbots_tf_buffer.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@ class Buffer {
3939
py_tf2_ros.attr("TimeoutException"));
4040

4141
// get node name from python node object
42-
rcl_node_t *node_handle = (rcl_node_t *)node.attr("handle").attr("pointer").cast<size_t>();
42+
rcl_node_t *node_handle =
43+
static_cast<rcl_node_t *>(reinterpret_cast<void *>(node.attr("handle").attr("pointer").cast<size_t>()));
4344
const char *node_name = rcl_node_get_name(node_handle);
4445
// create node with name <python_node_name>_tf
4546
node_ = std::make_shared<rclcpp::Node>((std::string(node_name) + "_tf").c_str());

bitbots_misc/bitbots_utils/src/utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "bitbots_utils/utils.hpp"
1+
#include <bitbots_utils/utils.hpp>
22

33
namespace bitbots_utils {
44

bitbots_motion/bitbots_dynamic_kick/include/bitbots_dynamic_kick/kick_ik.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ namespace bitbots_dynamic_kick {
1212

1313
class KickIK : public bitbots_splines::AbstractIK<KickPositions> {
1414
public:
15-
KickIK() = default;
15+
KickIK() : legs_joints_group_(), left_leg_joints_group_(), right_leg_joints_group_(){};
1616
void init(moveit::core::RobotModelPtr kinematic_model) override;
1717
bitbots_splines::JointGoals calculate(const KickPositions &positions) override;
1818
void reset() override;

bitbots_motion/bitbots_dynamic_kick/src/kick_engine.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
1-
#include "bitbots_dynamic_kick/kick_engine.hpp"
2-
1+
#include <bitbots_dynamic_kick/kick_engine.hpp>
32
#include <utility>
43

54
namespace bitbots_dynamic_kick {

bitbots_motion/bitbots_dynamic_kick/src/kick_ik.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "bitbots_dynamic_kick/kick_ik.hpp"
1+
#include <bitbots_dynamic_kick/kick_ik.hpp>
22

33
namespace bitbots_dynamic_kick {
44

bitbots_motion/bitbots_dynamic_kick/src/kick_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "bitbots_dynamic_kick/kick_node.hpp"
1+
#include <bitbots_dynamic_kick/kick_node.hpp>
22

33
namespace bitbots_dynamic_kick {
44
using namespace std::chrono_literals;

bitbots_motion/bitbots_dynamic_kick/src/stabilizer.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "bitbots_dynamic_kick/stabilizer.hpp"
1+
#include <bitbots_dynamic_kick/stabilizer.hpp>
22

33
namespace bitbots_dynamic_kick {
44

bitbots_motion/bitbots_dynamic_kick/src/visualizer.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
1-
#include "bitbots_dynamic_kick/visualizer.hpp"
2-
1+
#include <bitbots_dynamic_kick/visualizer.hpp>
32
#include <bitbots_splines/pose_spline.hpp>
43

54
namespace bitbots_dynamic_kick {

bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_engine.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,13 +9,13 @@
99
#include <bitbots_splines/smooth_spline.hpp>
1010
#include <bitbots_splines/spline_container.hpp>
1111
#include <cmath>
12+
#include <dynup_parameters.hpp>
1213
#include <optional>
1314
#include <rclcpp/rclcpp.hpp>
1415
#include <string>
1516
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1617
#include <visualization_msgs/msg/marker.hpp>
1718

18-
#include "dynup_parameters.hpp"
1919
#include "dynup_stabilizer.hpp"
2020

2121
namespace bitbots_dynup {

bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,10 @@
77
#include <tf2/convert.h>
88

99
#include <bitbots_splines/abstract_ik.hpp>
10+
#include <dynup_parameters.hpp>
1011
#include <sensor_msgs/msg/joint_state.hpp>
1112
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1213

13-
#include "dynup_parameters.hpp"
1414
#include "dynup_utils.hpp"
1515

1616
namespace bitbots_dynup {

bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_node.hpp

+7-8
Original file line numberDiff line numberDiff line change
@@ -11,30 +11,29 @@
1111
#include <tf2_ros/transform_listener.h>
1212
#include <unistd.h>
1313

14+
#include <bitbots_dynup/dynup_engine.hpp>
15+
#include <bitbots_dynup/dynup_ik.hpp>
16+
#include <bitbots_dynup/dynup_stabilizer.hpp>
1417
#include <bitbots_dynup/msg/dynup_poses.hpp>
18+
#include <bitbots_dynup/visualizer.hpp>
19+
#include <bitbots_msgs/action/dynup.hpp>
1520
#include <bitbots_msgs/msg/joint_command.hpp>
1621
#include <bitbots_utils/utils.hpp>
1722
#include <cmath>
23+
#include <dynup_parameters.hpp>
1824
#include <geometry_msgs/msg/pose.hpp>
1925
#include <geometry_msgs/msg/pose_array.hpp>
2026
#include <geometry_msgs/msg/pose_stamped.hpp>
2127
#include <optional>
2228
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
2329
#include <rclcpp/rclcpp.hpp>
30+
#include <rclcpp_action/rclcpp_action.hpp>
2431
#include <sensor_msgs/msg/imu.hpp>
2532
#include <std_msgs/msg/char.hpp>
2633
#include <string>
2734
#include <tf2_eigen/tf2_eigen.hpp>
2835
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
2936

30-
#include "bitbots_dynup/dynup_engine.hpp"
31-
#include "bitbots_dynup/dynup_ik.hpp"
32-
#include "bitbots_dynup/dynup_stabilizer.hpp"
33-
#include "bitbots_dynup/visualizer.hpp"
34-
#include "bitbots_msgs/action/dynup.hpp"
35-
#include "dynup_parameters.hpp"
36-
#include "rclcpp_action/rclcpp_action.hpp"
37-
3837
namespace bitbots_dynup {
3938
using DynupGoal = bitbots_msgs::action::Dynup;
4039
using DynupGoalHandle = rclcpp_action::ServerGoalHandle<DynupGoal>;

bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_pywrapper.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -4,14 +4,13 @@
44
#include <pybind11/pybind11.h>
55
#include <pybind11/stl.h>
66

7+
#include <bitbots_dynup/dynup_node.hpp>
8+
#include <bitbots_dynup/dynup_utils.hpp>
79
#include <iostream>
810
#include <map>
911
#include <rclcpp/rclcpp.hpp>
1012
#include <ros2_python_extension/serialization.hpp>
1113

12-
#include "bitbots_dynup/dynup_node.hpp"
13-
#include "bitbots_dynup/dynup_utils.hpp"
14-
1514
namespace py = pybind11;
1615
using namespace ros2_python_extension;
1716

bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_stabilizer.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,12 +6,12 @@
66
#include <Eigen/Geometry>
77
#include <bitbots_splines/abstract_stabilizer.hpp>
88
#include <control_toolbox/pid_ros.hpp>
9+
#include <dynup_parameters.hpp>
910
#include <optional>
1011
#include <sensor_msgs/msg/imu.hpp>
1112
#include <tf2_eigen/tf2_eigen.hpp>
1213
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1314

14-
#include "dynup_parameters.hpp"
1515
#include "dynup_utils.hpp"
1616
namespace bitbots_dynup {
1717

bitbots_motion/bitbots_dynup/include/bitbots_dynup/visualizer.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -11,14 +11,13 @@
1111
#include <bitbots_splines/abstract_visualizer.hpp>
1212
#include <bitbots_splines/smooth_spline.hpp>
1313
#include <bitbots_splines/spline_container.hpp>
14+
#include <dynup_parameters.hpp>
1415
#include <geometry_msgs/msg/pose_stamped.hpp>
1516
#include <rclcpp/rclcpp.hpp>
1617
#include <string>
1718
#include <tf2_eigen/tf2_eigen.hpp>
1819
#include <visualization_msgs/msg/marker_array.hpp>
1920

20-
#include "dynup_parameters.hpp"
21-
2221
namespace bitbots_dynup {
2322

2423
class Visualizer : bitbots_splines::AbstractVisualizer {

bitbots_motion/bitbots_dynup/src/dynup_engine.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
1-
#include "bitbots_dynup/dynup_engine.hpp"
2-
1+
#include <bitbots_dynup/dynup_engine.hpp>
32
#include <rclcpp/rclcpp.hpp>
43

54
namespace bitbots_dynup {

bitbots_motion/bitbots_dynup/src/dynup_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "bitbots_dynup/dynup_node.hpp"
1+
#include <bitbots_dynup/dynup_node.hpp>
22

33
namespace bitbots_dynup {
44
using namespace std::chrono_literals;

0 commit comments

Comments
 (0)