From b9f8dde44e45510f2d0dd19a3026362d59be2fc7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jun 2022 16:01:48 +0900 Subject: [PATCH] fix humble CI Signed-off-by: Takayuki Murooka --- planning/obstacle_cruise_planner/src/node.cpp | 2 +- .../optimization_based_planner.cpp | 7 ++++++- .../src/optimization_based_planner/resample.cpp | 2 +- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 47fc34c6be8ba..45bab678c98b7 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -200,7 +200,7 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & debug_cruise_wall_marker_pub_ = create_publisher("~/debug/cruise_wall_marker", 1); debug_stop_wall_marker_pub_ = - create_publisher("~/debug/stop_wall_marker", 1); + create_publisher("~/virtual_wall", 1); debug_marker_pub_ = create_publisher("~/debug/marker", 1); // longitudinal_info diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp index 4f5e273f6e230..08806fd0dc43a 100644 --- a/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp @@ -20,8 +20,13 @@ #include "obstacle_cruise_planner/utils.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" -#include +#ifdef ROS_DISTRO_GALACTIC #include +#else +#include +#endif + +#include constexpr double ZERO_VEL_THRESHOLD = 0.01; constexpr double CLOSE_S_DIST_THRESHOLD = 1e-3; diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp index 4c695c7961f72..a629abca7f0dd 100644 --- a/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/resample.cpp @@ -108,7 +108,7 @@ geometry_msgs::msg::Pose lerpByPose( tf2::slerp(tf_transform1.getRotation(), tf_transform2.getRotation(), t); geometry_msgs::msg::Pose pose; - pose.position = toMsg(tf_point); + pose.position = ::toMsg(tf_point); pose.orientation = tf2::toMsg(tf_quaternion); return pose; }