Skip to content

Commit

Permalink
Merge pull request #33 from Mailamaca/ros2_humble
Browse files Browse the repository at this point in the history
Fix compatibility with ros 2 humble.
  • Loading branch information
JWhitleyWork authored Mar 27, 2023
2 parents be0b42c + ce260f8 commit 153998d
Show file tree
Hide file tree
Showing 7 changed files with 33 additions and 28 deletions.
3 changes: 0 additions & 3 deletions .github/workflows/ros2-ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,6 @@ jobs:
- {
ros_distro: "humble"
}
- {
ros_distro: "foxy"
}
runs-on: ubuntu-latest
container:
image: ros:${{ matrix.config.ros_distro }}
Expand Down
9 changes: 5 additions & 4 deletions vesc_ackermann/include/vesc_ackermann/vesc_to_odom.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,16 @@
#ifndef VESC_ACKERMANN__VESC_TO_ODOM_HPP_
#define VESC_ACKERMANN__VESC_TO_ODOM_HPP_

#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/float64.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <vesc_msgs/msg/vesc_state_stamped.hpp>

#include <memory>
#include <string>

#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/float64.hpp>
#include <vesc_msgs/msg/vesc_state_stamped.hpp>

namespace vesc_ackermann
{

Expand Down
16 changes: 9 additions & 7 deletions vesc_ackermann/src/ackermann_to_vesc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@

#include "vesc_ackermann/ackermann_to_vesc.hpp"

#include <ackermann_msgs/msg/ackermann_drive_stamped.hpp>
#include <std_msgs/msg/float64.hpp>

#include <cmath>
#include <sstream>
#include <string>

#include <ackermann_msgs/msg/ackermann_drive_stamped.hpp>
#include <std_msgs/msg/float64.hpp>

namespace vesc_ackermann
{

Expand All @@ -48,10 +48,12 @@ AckermannToVesc::AckermannToVesc(const rclcpp::NodeOptions & options)
: Node("ackermann_to_vesc_node", options)
{
// get conversion parameters
speed_to_erpm_gain_ = declare_parameter("speed_to_erpm_gain").get<double>();
speed_to_erpm_offset_ = declare_parameter("speed_to_erpm_offset").get<double>();
steering_to_servo_gain_ = declare_parameter("steering_angle_to_servo_gain").get<double>();
steering_to_servo_offset_ = declare_parameter("steering_angle_to_servo_offset").get<double>();
speed_to_erpm_gain_ = declare_parameter<double>("speed_to_erpm_gain");
speed_to_erpm_offset_ = declare_parameter<double>("speed_to_erpm_offset");
steering_to_servo_gain_ =
declare_parameter<double>("steering_angle_to_servo_gain");
steering_to_servo_offset_ =
declare_parameter<double>("steering_angle_to_servo_offset");

// create publishers to vesc electric-RPM (speed) and servo commands
erpm_pub_ = create_publisher<Float64>("commands/motor/speed", 10);
Expand Down
18 changes: 10 additions & 8 deletions vesc_ackermann/src/vesc_to_odom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,12 @@

#include "vesc_ackermann/vesc_to_odom.hpp"

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <vesc_msgs/msg/vesc_state_stamped.hpp>

#include <cmath>
#include <string>

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <vesc_msgs/msg/vesc_state_stamped.hpp>

namespace vesc_ackermann
{

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

speed_to_erpm_gain_ = declare_parameter("speed_to_erpm_gain").get<double>();
speed_to_erpm_offset_ = declare_parameter("speed_to_erpm_offset").get<double>();
speed_to_erpm_gain_ = declare_parameter<double>("speed_to_erpm_gain");
speed_to_erpm_offset_ = declare_parameter<double>("speed_to_erpm_offset");

if (use_servo_cmd_) {
steering_to_servo_gain_ = declare_parameter("steering_angle_to_servo_gain").get<double>();
steering_to_servo_offset_ = declare_parameter("steering_angle_to_servo_offset").get<double>();
wheelbase_ = declare_parameter("wheelbase").get<double>();
steering_to_servo_gain_ =
declare_parameter<double>("steering_angle_to_servo_gain");
steering_to_servo_offset_ =
declare_parameter<double>("steering_angle_to_servo_offset");
wheelbase_ = declare_parameter<double>("wheelbase");
}

publish_tf_ = declare_parameter("publish_tf", publish_tf_);
Expand Down
7 changes: 4 additions & 3 deletions vesc_driver/include/vesc_driver/vesc_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,17 @@
#ifndef VESC_DRIVER__VESC_DRIVER_HPP_
#define VESC_DRIVER__VESC_DRIVER_HPP_

#include <experimental/optional>
#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <std_msgs/msg/float64.hpp>
#include <vesc_msgs/msg/vesc_state.hpp>
#include <vesc_msgs/msg/vesc_state_stamped.hpp>
#include <vesc_msgs/msg/vesc_imu.hpp>
#include <vesc_msgs/msg/vesc_imu_stamped.hpp>
#include <experimental/optional>
#include <memory>
#include <string>

#include "vesc_driver/vesc_interface.hpp"
#include "vesc_driver/vesc_packet.hpp"
Expand Down
6 changes: 4 additions & 2 deletions vesc_driver/src/vesc_device_namer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,11 @@

#include <unistd.h>
#include <stdlib.h>
#include <vesc_driver/vesc_device_uuid_lookup.hpp>
#include <string>

#include <iostream>
#include <string>

#include <vesc_driver/vesc_device_uuid_lookup.hpp>

int main(int argc, char ** argv)
{
Expand Down
2 changes: 1 addition & 1 deletion vesc_driver/src/vesc_packet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -576,7 +576,7 @@ double VescPacketImu::getFloat32Auto(uint32_t * idx) const

int e = (res >> 23) & 0xFF;
int fr = res & 0x7FFFFF;
bool negative = res & (1 << 31);
bool negative = res & (1u << 31);

float f = 0.0;
if (e != 0 || fr != 0) {
Expand Down

0 comments on commit 153998d

Please sign in to comment.