Skip to content

Commit

Permalink
feat!: replace tier4_planning_msgs/PathWithLaneId with autoware_inter…
Browse files Browse the repository at this point in the history
…nal_planning_msgs/PathWithLaneId

Signed-off-by: mitsudome-r <[email protected]>
  • Loading branch information
mitsudome-r committed Jan 27, 2025
1 parent c12383c commit ea17cd0
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ using autoware_planning_msgs::msg::Path;
using autoware_planning_msgs::msg::PathPoint;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using tier4_planning_msgs::msg::PathWithLaneId;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
} // namespace autoware::static_centerline_generator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"

#include <iostream>
#include <map>
Expand All @@ -39,7 +39,7 @@ using autoware_planning_msgs::msg::Path;
using autoware_planning_msgs::msg::Trajectory;
using nav_msgs::msg::Odometry;
using planning_debug_tools::msg::TrajectoryDebugInfo;
using tier4_planning_msgs::msg::PathWithLaneId;
using autoware_internal_planning_msgs::msg::PathWithLaneId;

template <typename T>
class TrajectoryAnalyzer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"

#include <vector>

Expand All @@ -33,7 +33,7 @@ using autoware::universe_utils::getPoint;
using autoware::universe_utils::getRPY;
using autoware_planning_msgs::msg::PathPoint;
using autoware_planning_msgs::msg::TrajectoryPoint;
using tier4_planning_msgs::msg::PathPointWithLaneId;
using autoware_internal_planning_msgs::msg::PathPointWithLaneId;

double getVelocity(const PathPoint & p)
{
Expand Down

0 comments on commit ea17cd0

Please sign in to comment.