Skip to content

Commit

Permalink
include tf2_geometry_msgs earlier to avoid missing symbols (backport #…
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson authored Nov 8, 2024
1 parent 13ce75c commit 83ad5eb
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@

#include <rclcpp/rclcpp.hpp>
#include <robot_calibration_msgs/msg/calibration_data.hpp>
// Including this before buffer.h as a workaround for missing symbols
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/buffer.h>

namespace robot_calibration
Expand Down
1 change: 0 additions & 1 deletion robot_calibration/src/finders/plane_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include <robot_calibration/finders/plane_finder.hpp>
#include <robot_calibration/util/eigen_geometry.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

static const rclcpp::Logger LOGGER = rclcpp::get_logger("plane_finder");

Expand Down
1 change: 0 additions & 1 deletion robot_calibration/src/finders/robot_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <math.h>
#include <robot_calibration/finders/robot_finder.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

static const rclcpp::Logger LOGGER = rclcpp::get_logger("robot_finder");

Expand Down
1 change: 0 additions & 1 deletion robot_calibration/src/finders/scan_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <math.h>
#include <robot_calibration/finders/scan_finder.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

static const rclcpp::Logger LOGGER = rclcpp::get_logger("scan_finder");

Expand Down

0 comments on commit 83ad5eb

Please sign in to comment.