Skip to content

Commit

Permalink
feat(motion_velocity_planner): use Float64Stamped in autoware_interna…
Browse files Browse the repository at this point in the history
…l_debug_msgs (#9745)

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 authored Dec 24, 2024
1 parent c16e656 commit 8865d0f
Show file tree
Hide file tree
Showing 8 changed files with 23 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,9 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
processing_diag_publisher_ = std::make_shared<autoware::universe_utils::ProcessingTimePublisher>(
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);
processing_time_publisher_ =
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);

using autoware::universe_utils::getOrDeclareParameter;
auto & p = params_;
Expand Down Expand Up @@ -190,7 +191,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan(
processing_times["collisions"] = collisions_duration_us / 1000;
processing_times["Total"] = total_time_us / 1000;
processing_diag_publisher_->publish(processing_times);
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
processing_time_msg.stamp = clock_->now();
processing_time_msg.data = processing_times["Total"];
processing_time_publisher_->publish(processing_time_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,9 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
processing_diag_publisher_ = std::make_shared<autoware::universe_utils::ProcessingTimePublisher>(
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);
processing_time_publisher_ =
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);

const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
vehicle_lateral_offset_ = static_cast<double>(vehicle_info.max_lateral_offset_m);
Expand Down Expand Up @@ -236,7 +237,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan(
processing_times["slowdowns"] = slowdowns_us / 1000;
processing_times["Total"] = total_us / 1000;
processing_diag_publisher_->publish(processing_times);
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
processing_time_msg.stamp = clock_->now();
processing_time_msg.data = processing_times["Total"];
processing_time_publisher_->publish(processing_time_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,9 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name)
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
processing_diag_publisher_ = std::make_shared<universe_utils::ProcessingTimePublisher>(
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);
processing_time_publisher_ =
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/" + ns_ + "/processing_time_ms", 1);
}
void OutOfLaneModule::init_parameters(rclcpp::Node & node)
{
Expand Down Expand Up @@ -349,7 +350,7 @@ VelocityPlanningResult OutOfLaneModule::plan(
processing_times["publish_markers"] = pub_markers_us / 1000;
processing_times["Total"] = total_time_us / 1000;
processing_diag_publisher_->publish(processing_times);
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
processing_time_msg.stamp = clock_->now();
processing_time_msg.data = processing_times["Total"];
processing_time_publisher_->publish(processing_time_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include <autoware/universe_utils/ros/processing_time_publisher.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>

#include <memory>
#include <string>
Expand All @@ -47,7 +47,8 @@ class PluginModuleInterface
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_publisher_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr virtual_wall_publisher_;
std::shared_ptr<autoware::universe_utils::ProcessingTimePublisher> processing_diag_publisher_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
processing_time_publisher_;
autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{};
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand All @@ -27,7 +28,6 @@
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
<depend>rclcpp</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_motion_velocity_planner_common</depend>
Expand All @@ -37,7 +38,6 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions &
this->create_publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
"~/output/velocity_factors", 1);
processing_time_publisher_ =
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/processing_time_ms", 1);
debug_viz_pub_ =
this->create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/markers", 1);
metrics_pub_ = this->create_publisher<MetricArray>("~/metrics", 1);
Expand Down Expand Up @@ -299,7 +300,7 @@ void MotionVelocityPlannerNode::on_trajectory(
trajectory_pub_, output_trajectory_msg.header.stamp);
processing_times["Total"] = stop_watch.toc("Total");
processing_diag_publisher_.publish(processing_times);
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
processing_time_msg.stamp = get_clock()->now();
processing_time_msg.data = processing_times["Total"];
processing_time_publisher_->publish(processing_time_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,14 @@
#include <autoware_motion_velocity_planner_node/srv/unload_plugin.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/traffic_signal_array.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <tf2_ros/buffer.h>
Expand Down Expand Up @@ -97,7 +97,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node
velocity_factor_publisher_;
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{
this, "~/debug/processing_time_ms_diag"};
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
processing_time_publisher_;
autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this};
rclcpp::Publisher<MetricArray>::SharedPtr metrics_pub_;

Expand Down

0 comments on commit 8865d0f

Please sign in to comment.