Skip to content

Commit

Permalink
feat(motion_planning): use StringStamped in autoware_internal_debug_m…
Browse files Browse the repository at this point in the history
…sgs (autowarefoundation#9742)

feat(motion planning): use StringStamped in autoware_internal_debug_msgs

Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 authored and kyoichi-sugahara committed Dec 25, 2024
1 parent 3b019b1 commit 54e5598
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_
#define AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_

#include "autoware_internal_debug_msgs/msg/string_stamped.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/path_point.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
Expand All @@ -25,7 +26,6 @@
#include "nav_msgs/msg/odometry.hpp"
#include "std_msgs/msg/header.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"
#include "tier4_debug_msgs/msg/string_stamped.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

namespace autoware::path_optimizer
Expand All @@ -43,8 +43,8 @@ using nav_msgs::msg::Odometry;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
// debug
using autoware_internal_debug_msgs::msg::StringStamped;
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_debug_msgs::msg::StringStamped;
} // namespace autoware::path_optimizer

#endif // AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_
1 change: 1 addition & 0 deletions planning/autoware_path_optimizer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_osqp_interface</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_
#define AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_

#include "autoware_internal_debug_msgs/msg/string_stamped.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/path_point.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
Expand All @@ -23,7 +24,6 @@
#include "nav_msgs/msg/odometry.hpp"
#include "std_msgs/msg/header.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"
#include "tier4_debug_msgs/msg/string_stamped.hpp"

namespace autoware::path_smoother
{
Expand All @@ -37,8 +37,8 @@ using autoware_planning_msgs::msg::TrajectoryPoint;
// navigation
using nav_msgs::msg::Odometry;
// debug
using autoware_internal_debug_msgs::msg::StringStamped;
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_debug_msgs::msg::StringStamped;
} // namespace autoware::path_smoother

#endif // AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_
1 change: 1 addition & 0 deletions planning/autoware_path_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_osqp_interface</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_
#define AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_

#include "autoware_internal_debug_msgs/msg/string_stamped.hpp"
#include "autoware_perception_msgs/msg/predicted_objects.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/path_point.hpp"
Expand All @@ -25,7 +26,6 @@
#include "geometry_msgs/msg/twist.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "std_msgs/msg/header.hpp"
#include "tier4_debug_msgs/msg/string_stamped.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

namespace autoware::path_sampler
Expand All @@ -45,7 +45,7 @@ using nav_msgs::msg::Odometry;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
// debug
using tier4_debug_msgs::msg::StringStamped;
using autoware_internal_debug_msgs::msg::StringStamped;
} // namespace autoware::path_sampler

#endif // AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<depend>autoware_bezier_sampler</depend>
<depend>autoware_frenet_planner</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
Expand Down

0 comments on commit 54e5598

Please sign in to comment.