Skip to content

Commit

Permalink
feat(behavior planning): use StringStamped in autoware_internal_debug…
Browse files Browse the repository at this point in the history
…_msgs

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Dec 23, 2024
1 parent 067ee7a commit 5d20536
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ using SceneModulePtr = std::shared_ptr<SceneModuleInterface>;
using SceneModuleManagerPtr = std::shared_ptr<SceneModuleManagerInterface>;
using DebugPublisher = autoware::universe_utils::DebugPublisher;
using DebugDoubleMsg = tier4_debug_msgs::msg::Float64Stamped;
using DebugStringMsg = tier4_debug_msgs::msg::StringStamped;
using DebugStringMsg = autoware_internal_debug_msgs::msg::StringStamped;

struct SceneModuleUpdateInfo
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_grid_map_utils</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,11 +153,11 @@ StopFactor createStopFactor(
return stop_factor;
}

tier4_debug_msgs::msg::StringStamped createStringStampedMessage(
autoware_internal_debug_msgs::msg::StringStamped createStringStampedMessage(
const rclcpp::Time & now, const int64_t module_id_,
const std::vector<std::tuple<std::string, CollisionPoint, CollisionState>> & collision_points)
{
tier4_debug_msgs::msg::StringStamped msg;
autoware_internal_debug_msgs::msg::StringStamped msg;
msg.stamp = now;
for (const auto & collision_point : collision_points) {
std::stringstream ss;
Expand Down Expand Up @@ -199,8 +199,8 @@ CrosswalkModule::CrosswalkModule(

road_ = lanelet_map_ptr->laneletLayer.get(lane_id);

collision_info_pub_ =
node.create_publisher<tier4_debug_msgs::msg::StringStamped>("~/debug/collision_info", 1);
collision_info_pub_ = node.create_publisher<autoware_internal_debug_msgs::msg::StringStamped>(
"~/debug/collision_info", 1);
}

bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/string_stamped.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>

#include <boost/assert.hpp>
#include <boost/assign/list_of.hpp>
Expand Down Expand Up @@ -456,7 +456,8 @@ class CrosswalkModule : public SceneModuleInterface

const int64_t module_id_;

rclcpp::Publisher<tier4_debug_msgs::msg::StringStamped>::SharedPtr collision_info_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::StringStamped>::SharedPtr
collision_info_pub_;

lanelet::ConstLanelet crosswalk_;

Expand Down

0 comments on commit 5d20536

Please sign in to comment.