Skip to content

Commit

Permalink
Changes according to make format and changed ros distro to jazzy
Browse files Browse the repository at this point in the history
  • Loading branch information
JanNiklasFeld committed Nov 24, 2024
1 parent 3c0b69c commit dacfb4e
Show file tree
Hide file tree
Showing 66 changed files with 125 additions and 153 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@ jobs:
- name: Build packages
run: |
. /opt/ros/iron/setup.sh
. /opt/ros/jazzy/setup.sh
colcon build --symlink-install
working-directory: /colcon_ws

- name: Test packages
run: |
# Source workspace
. /opt/ros/iron/setup.sh
. /opt/ros/jazzy/setup.sh
. install/setup.sh
# Run tests for all packages
colcon test --event-handlers console_direct+ --return-code-on-test-failure --parallel-workers 1
Expand Down
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ repos:
- id: cppcheck
args:
- "--inline-suppr"
- "--suppress=missingInclude"
- "--suppress=missingIncludeSystem"
- "--suppress=unmatchedSuppression"
- "--suppress=unusedFunction"
- "--suppress=unusedStructMember"
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

[![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)
[![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)
[![ROS Version Iron](https://img.shields.io/badge/ROS%20Version-Iron-ab8c71)](https://docs.ros.org/en/iron/index.html)
[![ROS Version Jazzy](https://img.shields.io/badge/ROS%20Version-Jazzy-00b8ff)](https://docs.ros.org/en/jazzy/index.html)

This git repository contains all RoboCup-related code and documentation from the Hamburg Bit-Bots team.
All code is written as individual ROS 2 packages targeting Ubuntu.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#ifndef BITBOTS_ROS_CONTROL_INCLUDE_BITBOTS_ROS_CONTROL_UTILS_H_
#define BITBOTS_ROS_CONTROL_INCLUDE_BITBOTS_ROS_CONTROL_UTILS_H_

#include "bitbots_msgs/msg/audio.hpp"
#include "rclcpp/rclcpp.hpp"
#include <bitbots_msgs/msg/audio.hpp>
#include <rclcpp/rclcpp.hpp>

namespace bitbots_ros_control {

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

uint16_t dxlMakeword(uint64_t a, uint64_t b);
uint32_t dxlMakedword(uint64_t a, uint64_t b);
float dxlMakeFloat(uint8_t* data);
float dxlMakeFloat(const uint8_t* data);

std::string gyroRangeToString(uint8_t range);
std::string accelRangeToString(uint8_t range);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ void DynamixelServoHardwareInterface::individualTorqueCb(bitbots_msgs::msg::Join
RCLCPP_WARN(nh_->get_logger(), "Couldn't set torque for servo %s ", msg.joint_names[i].c_str());
}
}
for (auto &bus : bus_interfaces_) {
for (const auto &bus : bus_interfaces_) {
bus->switch_individual_torque_ = true;
}
}
Expand All @@ -157,7 +157,7 @@ void DynamixelServoHardwareInterface::setTorqueCb(std_msgs::msg::Bool::SharedPtr
/**
* This saves the given required value, so that it can be written to the servos in the write method
*/
for (auto &bus : bus_interfaces_) {
for (const auto &bus : bus_interfaces_) {
bus->goal_torque_ = enabled->data;
}
for (size_t j = 0; j < joint_names_.size(); j++) {
Expand Down Expand Up @@ -196,7 +196,7 @@ void DynamixelServoHardwareInterface::write(const rclcpp::Time &t, const rclcpp:
// set all values from controller to the buses
// todo improve performance
int i = 0;
for (auto &bus : bus_interfaces_) {
for (const auto &bus : bus_interfaces_) {
for (int j = 0; j < bus->joint_count_; j++) {
bus->goal_position_[j] = goal_position_[i];
bus->goal_velocity_[j] = goal_velocity_[i];
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ bool ServoBusInterface::writeROMRAM(bool first_time) {
// Allocate memory for the values in the driver
std::vector<int> values(joint_names_.size());
// Iterate over parameter names
for (auto register_name : parameter_names) {
for (const auto &register_name : parameter_names) {
// Get the value for each joint
for (size_t num = 0; num < joint_names_.size(); num++) {
// Get the value from the cache
Expand Down
2 changes: 1 addition & 1 deletion bitbots_lowlevel/bitbots_ros_control/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ uint32_t dxlMakedword(uint64_t a, uint64_t b) {
return uint32_t(uint16_t(a & 0xffff) | uint32_t(uint16_t(b & 0xffff) << 16));
}

float dxlMakeFloat(uint8_t* data) {
float dxlMakeFloat(const uint8_t* data) {
float f;
uint32_t b = dxlMakedword(dxlMakeword(data[0], data[1]), dxlMakeword(data[2], data[3]));
memcpy(&f, &b, sizeof(f));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -307,7 +307,7 @@ void WolfgangHardwareInterface::write(const rclcpp::Time &t, const rclcpp::Durat
}
if (!bus_start_time_ || t > bus_start_time_.value()) {
if (bus_first_write_) {
for (std::vector<std::shared_ptr<HardwareInterface>> &port_interfaces : interfaces_) {
for (std::vector<std::shared_ptr<HardwareInterface>> const &port_interfaces : interfaces_) {
for (std::shared_ptr<HardwareInterface> interface : port_interfaces) {
interface->restoreAfterPowerCycle();
}
Expand Down
6 changes: 3 additions & 3 deletions bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,13 @@
#include <iostream>
#include <memory>
#include <opencv2/imgproc/imgproc.hpp>
#include <pylon_camera_parameters.hpp>
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
#include <rclcpp/logger.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <vector>

#include "pylon_camera_parameters.hpp"

using std::placeholders::_1, std::placeholders::_2;
using namespace Pylon;

Expand Down Expand Up @@ -271,7 +270,8 @@ class BaslerCamera {
}

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

// Create cv::Mat for color image
cv::Mat color(image.size(), CV_MAKETYPE(CV_8U, 3));
Expand Down
2 changes: 1 addition & 1 deletion bitbots_misc/bitbots_docs/docs/manual/testing/testing.rst
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ Compile (compiles)
------------------

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

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

**3. Run Webots Simulation**

Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
Software installation with ROS2
===============================

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

**TLDR**: single command setup
------------------------------

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

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

**0. Use Ubuntu 22.04**
**0. Use Ubuntu 24.04**

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

If you are not already using Ubuntu 22.04, consider installing it on your system (perhaps as a dual boot?).
If you are not already using Ubuntu 24.04, consider installing it on your system (perhaps as a dual boot?).
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.

**1. Setup and Install ROS 2**

- 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
- 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
- Install additional dependencies:

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

**4. Setup colcon workspace**

`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.
`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.
The colcon workspace is where your source code gets build and where we use colcon.

- Create colcon workspace directory (typically ``~/colcon_ws/``)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,14 @@ Navigate to your colcon workspace.

Source ros

`source /opt/ros/iron/setup.zsh`
`source /opt/ros/jazzy/setup.zsh`

Open VSCode

`code .`

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

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

Expand Down
3 changes: 2 additions & 1 deletion bitbots_misc/bitbots_tf_buffer/src/bitbots_tf_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ class Buffer {
py_tf2_ros.attr("TimeoutException"));

// get node name from python node object
rcl_node_t *node_handle = (rcl_node_t *)node.attr("handle").attr("pointer").cast<size_t>();
rcl_node_t *node_handle =
static_cast<rcl_node_t *>(reinterpret_cast<void *>(node.attr("handle").attr("pointer").cast<size_t>()));
const char *node_name = rcl_node_get_name(node_handle);
// create node with name <python_node_name>_tf
node_ = std::make_shared<rclcpp::Node>((std::string(node_name) + "_tf").c_str());
Expand Down
2 changes: 1 addition & 1 deletion bitbots_misc/bitbots_utils/src/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_utils/utils.hpp"
#include <bitbots_utils/utils.hpp>

namespace bitbots_utils {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace bitbots_dynamic_kick {

class KickIK : public bitbots_splines::AbstractIK<KickPositions> {
public:
KickIK() = default;
KickIK() : legs_joints_group_(), left_leg_joints_group_(), right_leg_joints_group_(){};
void init(moveit::core::RobotModelPtr kinematic_model) override;
bitbots_splines::JointGoals calculate(const KickPositions &positions) override;
void reset() override;
Expand Down
3 changes: 1 addition & 2 deletions bitbots_motion/bitbots_dynamic_kick/src/kick_engine.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "bitbots_dynamic_kick/kick_engine.hpp"

#include <bitbots_dynamic_kick/kick_engine.hpp>
#include <utility>

namespace bitbots_dynamic_kick {
Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/kick_ik.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/kick_ik.hpp"
#include <bitbots_dynamic_kick/kick_ik.hpp>

namespace bitbots_dynamic_kick {

Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/kick_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/kick_node.hpp"
#include <bitbots_dynamic_kick/kick_node.hpp>

namespace bitbots_dynamic_kick {
using namespace std::chrono_literals;
Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/stabilizer.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/stabilizer.hpp"
#include <bitbots_dynamic_kick/stabilizer.hpp>

namespace bitbots_dynamic_kick {

Expand Down
3 changes: 1 addition & 2 deletions bitbots_motion/bitbots_dynamic_kick/src/visualizer.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "bitbots_dynamic_kick/visualizer.hpp"

#include <bitbots_dynamic_kick/visualizer.hpp>
#include <bitbots_splines/pose_spline.hpp>

namespace bitbots_dynamic_kick {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@
#include <bitbots_splines/smooth_spline.hpp>
#include <bitbots_splines/spline_container.hpp>
#include <cmath>
#include <dynup_parameters.hpp>
#include <optional>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <visualization_msgs/msg/marker.hpp>

#include "dynup_parameters.hpp"
#include "dynup_stabilizer.hpp"

namespace bitbots_dynup {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
#include <tf2/convert.h>

#include <bitbots_splines/abstract_ik.hpp>
#include <dynup_parameters.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "dynup_parameters.hpp"
#include "dynup_utils.hpp"

namespace bitbots_dynup {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,30 +11,29 @@
#include <tf2_ros/transform_listener.h>
#include <unistd.h>

#include <bitbots_dynup/dynup_engine.hpp>
#include <bitbots_dynup/dynup_ik.hpp>
#include <bitbots_dynup/dynup_stabilizer.hpp>
#include <bitbots_dynup/msg/dynup_poses.hpp>
#include <bitbots_dynup/visualizer.hpp>
#include <bitbots_msgs/action/dynup.hpp>
#include <bitbots_msgs/msg/joint_command.hpp>
#include <bitbots_utils/utils.hpp>
#include <cmath>
#include <dynup_parameters.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <optional>
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <std_msgs/msg/char.hpp>
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "bitbots_dynup/dynup_engine.hpp"
#include "bitbots_dynup/dynup_ik.hpp"
#include "bitbots_dynup/dynup_stabilizer.hpp"
#include "bitbots_dynup/visualizer.hpp"
#include "bitbots_msgs/action/dynup.hpp"
#include "dynup_parameters.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

namespace bitbots_dynup {
using DynupGoal = bitbots_msgs::action::Dynup;
using DynupGoalHandle = rclcpp_action::ServerGoalHandle<DynupGoal>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,13 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include <bitbots_dynup/dynup_node.hpp>
#include <bitbots_dynup/dynup_utils.hpp>
#include <iostream>
#include <map>
#include <rclcpp/rclcpp.hpp>
#include <ros2_python_extension/serialization.hpp>

#include "bitbots_dynup/dynup_node.hpp"
#include "bitbots_dynup/dynup_utils.hpp"

namespace py = pybind11;
using namespace ros2_python_extension;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@
#include <Eigen/Geometry>
#include <bitbots_splines/abstract_stabilizer.hpp>
#include <control_toolbox/pid_ros.hpp>
#include <dynup_parameters.hpp>
#include <optional>
#include <sensor_msgs/msg/imu.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "dynup_parameters.hpp"
#include "dynup_utils.hpp"
namespace bitbots_dynup {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,13 @@
#include <bitbots_splines/abstract_visualizer.hpp>
#include <bitbots_splines/smooth_spline.hpp>
#include <bitbots_splines/spline_container.hpp>
#include <dynup_parameters.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include "dynup_parameters.hpp"

namespace bitbots_dynup {

class Visualizer : bitbots_splines::AbstractVisualizer {
Expand Down
3 changes: 1 addition & 2 deletions bitbots_motion/bitbots_dynup/src/dynup_engine.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "bitbots_dynup/dynup_engine.hpp"

#include <bitbots_dynup/dynup_engine.hpp>
#include <rclcpp/rclcpp.hpp>

namespace bitbots_dynup {
Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynup/src/dynup_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynup/dynup_node.hpp"
#include <bitbots_dynup/dynup_node.hpp>

namespace bitbots_dynup {
using namespace std::chrono_literals;
Expand Down
Loading

0 comments on commit dacfb4e

Please sign in to comment.