Skip to content

Commit 153998d

Browse files
authored
Merge pull request #33 from Mailamaca/ros2_humble
Fix compatibility with ros 2 humble.
2 parents be0b42c + ce260f8 commit 153998d

File tree

7 files changed

+33
-28
lines changed

7 files changed

+33
-28
lines changed

.github/workflows/ros2-ci.yaml

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,9 +18,6 @@ jobs:
1818
- {
1919
ros_distro: "humble"
2020
}
21-
- {
22-
ros_distro: "foxy"
23-
}
2421
runs-on: ubuntu-latest
2522
container:
2623
image: ros:${{ matrix.config.ros_distro }}

vesc_ackermann/include/vesc_ackermann/vesc_to_odom.hpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,15 +31,16 @@
3131
#ifndef VESC_ACKERMANN__VESC_TO_ODOM_HPP_
3232
#define VESC_ACKERMANN__VESC_TO_ODOM_HPP_
3333

34-
#include <nav_msgs/msg/odometry.hpp>
35-
#include <rclcpp/rclcpp.hpp>
36-
#include <std_msgs/msg/float64.hpp>
3734
#include <tf2_ros/transform_broadcaster.h>
38-
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
3935

4036
#include <memory>
4137
#include <string>
4238

39+
#include <nav_msgs/msg/odometry.hpp>
40+
#include <rclcpp/rclcpp.hpp>
41+
#include <std_msgs/msg/float64.hpp>
42+
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
43+
4344
namespace vesc_ackermann
4445
{
4546

vesc_ackermann/src/ackermann_to_vesc.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -30,13 +30,13 @@
3030

3131
#include "vesc_ackermann/ackermann_to_vesc.hpp"
3232

33-
#include <ackermann_msgs/msg/ackermann_drive_stamped.hpp>
34-
#include <std_msgs/msg/float64.hpp>
35-
3633
#include <cmath>
3734
#include <sstream>
3835
#include <string>
3936

37+
#include <ackermann_msgs/msg/ackermann_drive_stamped.hpp>
38+
#include <std_msgs/msg/float64.hpp>
39+
4040
namespace vesc_ackermann
4141
{
4242

@@ -48,10 +48,12 @@ AckermannToVesc::AckermannToVesc(const rclcpp::NodeOptions & options)
4848
: Node("ackermann_to_vesc_node", options)
4949
{
5050
// get conversion parameters
51-
speed_to_erpm_gain_ = declare_parameter("speed_to_erpm_gain").get<double>();
52-
speed_to_erpm_offset_ = declare_parameter("speed_to_erpm_offset").get<double>();
53-
steering_to_servo_gain_ = declare_parameter("steering_angle_to_servo_gain").get<double>();
54-
steering_to_servo_offset_ = declare_parameter("steering_angle_to_servo_offset").get<double>();
51+
speed_to_erpm_gain_ = declare_parameter<double>("speed_to_erpm_gain");
52+
speed_to_erpm_offset_ = declare_parameter<double>("speed_to_erpm_offset");
53+
steering_to_servo_gain_ =
54+
declare_parameter<double>("steering_angle_to_servo_gain");
55+
steering_to_servo_offset_ =
56+
declare_parameter<double>("steering_angle_to_servo_offset");
5557

5658
// create publishers to vesc electric-RPM (speed) and servo commands
5759
erpm_pub_ = create_publisher<Float64>("commands/motor/speed", 10);

vesc_ackermann/src/vesc_to_odom.cpp

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -30,12 +30,12 @@
3030

3131
#include "vesc_ackermann/vesc_to_odom.hpp"
3232

33-
#include <geometry_msgs/msg/transform_stamped.hpp>
34-
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
35-
3633
#include <cmath>
3734
#include <string>
3835

36+
#include <geometry_msgs/msg/transform_stamped.hpp>
37+
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
38+
3939
namespace vesc_ackermann
4040
{
4141

@@ -60,13 +60,15 @@ VescToOdom::VescToOdom(const rclcpp::NodeOptions & options)
6060
base_frame_ = declare_parameter("base_frame", base_frame_);
6161
use_servo_cmd_ = declare_parameter("use_servo_cmd_to_calc_angular_velocity", use_servo_cmd_);
6262

63-
speed_to_erpm_gain_ = declare_parameter("speed_to_erpm_gain").get<double>();
64-
speed_to_erpm_offset_ = declare_parameter("speed_to_erpm_offset").get<double>();
63+
speed_to_erpm_gain_ = declare_parameter<double>("speed_to_erpm_gain");
64+
speed_to_erpm_offset_ = declare_parameter<double>("speed_to_erpm_offset");
6565

6666
if (use_servo_cmd_) {
67-
steering_to_servo_gain_ = declare_parameter("steering_angle_to_servo_gain").get<double>();
68-
steering_to_servo_offset_ = declare_parameter("steering_angle_to_servo_offset").get<double>();
69-
wheelbase_ = declare_parameter("wheelbase").get<double>();
67+
steering_to_servo_gain_ =
68+
declare_parameter<double>("steering_angle_to_servo_gain");
69+
steering_to_servo_offset_ =
70+
declare_parameter<double>("steering_angle_to_servo_offset");
71+
wheelbase_ = declare_parameter<double>("wheelbase");
7072
}
7173

7274
publish_tf_ = declare_parameter("publish_tf", publish_tf_);

vesc_driver/include/vesc_driver/vesc_driver.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -31,16 +31,17 @@
3131
#ifndef VESC_DRIVER__VESC_DRIVER_HPP_
3232
#define VESC_DRIVER__VESC_DRIVER_HPP_
3333

34+
#include <experimental/optional>
35+
#include <memory>
36+
#include <string>
37+
3438
#include <rclcpp/rclcpp.hpp>
3539
#include <sensor_msgs/msg/imu.hpp>
3640
#include <std_msgs/msg/float64.hpp>
3741
#include <vesc_msgs/msg/vesc_state.hpp>
3842
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
3943
#include <vesc_msgs/msg/vesc_imu.hpp>
4044
#include <vesc_msgs/msg/vesc_imu_stamped.hpp>
41-
#include <experimental/optional>
42-
#include <memory>
43-
#include <string>
4445

4546
#include "vesc_driver/vesc_interface.hpp"
4647
#include "vesc_driver/vesc_packet.hpp"

vesc_driver/src/vesc_device_namer.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,11 @@
1616

1717
#include <unistd.h>
1818
#include <stdlib.h>
19-
#include <vesc_driver/vesc_device_uuid_lookup.hpp>
20-
#include <string>
19+
2120
#include <iostream>
21+
#include <string>
22+
23+
#include <vesc_driver/vesc_device_uuid_lookup.hpp>
2224

2325
int main(int argc, char ** argv)
2426
{

vesc_driver/src/vesc_packet.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -576,7 +576,7 @@ double VescPacketImu::getFloat32Auto(uint32_t * idx) const
576576

577577
int e = (res >> 23) & 0xFF;
578578
int fr = res & 0x7FFFFF;
579-
bool negative = res & (1 << 31);
579+
bool negative = res & (1u << 31);
580580

581581
float f = 0.0;
582582
if (e != 0 || fr != 0) {

0 commit comments

Comments
 (0)