Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(accel_brake_map_calibrator): modify build error in rolling #755

Merged
merged 1 commit into from
Apr 24, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,13 @@ ament_auto_add_executable(accel_brake_map_calibrator
)
ament_target_dependencies(accel_brake_map_calibrator)

# workaround to allow deprecated header to build on both galactic and rolling
if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0)
target_compile_definitions(accel_brake_map_calibrator PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,13 @@
#include "raw_vehicle_cmd_converter/brake_map.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#else
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#endif

#include "tier4_autoware_utils/planning/planning_marker_helper.hpp"
#include "tier4_autoware_utils/ros/transform_listener.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -984,7 +984,7 @@ T AccelBrakeMapCalibrator::getNearestTimeDataFromVec(
double nearest_time = std::numeric_limits<double>::max();
const double target_time = rclcpp::Time(base_data->header.stamp).seconds() - back_time;
T nearest_time_data;
for (const auto data : vec) {
for (const auto & data : vec) {
const double data_time = rclcpp::Time(data->header.stamp).seconds();
const auto delta_time = std::abs(target_time - data_time);
if (nearest_time > delta_time) {
Expand All @@ -1001,7 +1001,7 @@ DataStampedPtr AccelBrakeMapCalibrator::getNearestTimeDataFromVec(
double nearest_time = std::numeric_limits<double>::max();
const double target_time = base_data->data_time.seconds() - back_time;
DataStampedPtr nearest_time_data;
for (const auto data : vec) {
for (const auto & data : vec) {
const double data_time = data->data_time.seconds();
const auto delta_time = std::abs(target_time - data_time);
if (nearest_time > delta_time) {
Expand Down