Skip to content

Commit

Permalink
chore(obstacle_velocity_limiter): publish processing time as float (#…
Browse files Browse the repository at this point in the history
…5257)

Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe authored Oct 11, 2023
1 parent 82d9840 commit 2aa9d1c
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 5 deletions.
2 changes: 1 addition & 1 deletion planning/obstacle_velocity_limiter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ For example a value of `1` means all trajectory points will be evaluated while a
| ------------------------------- | ---------------------------------------- | -------------------------------------------------------- |
| `~/output/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Trajectory with adjusted velocities |
| `~/output/debug_markers` | `visualization_msgs/MarkerArray` | Debug markers (envelopes, obstacle polygons) |
| `~/output/runtime_microseconds` | `std_msgs/Int64` | Time taken to calculate the trajectory (in microseconds) |
| `~/output/runtime_microseconds` | `tier4_debug_msgs/Float64` | Time taken to calculate the trajectory (in microseconds) |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <std_msgs/msg/int64.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <boost/optional.hpp>
Expand All @@ -56,7 +56,7 @@ class ObstacleVelocityLimiterNode : public rclcpp::Node
pub_trajectory_; //!< @brief publisher for output trajectory
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
pub_debug_markers_; //!< @brief publisher for debug markers
rclcpp::Publisher<std_msgs::msg::Int64>::SharedPtr
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_runtime_; //!< @brief publisher for callback runtime
rclcpp::Subscription<Trajectory>::SharedPtr
sub_trajectory_; //!< @brief subscriber for reference trajectory
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,8 @@ ObstacleVelocityLimiterNode::ObstacleVelocityLimiterNode(const rclcpp::NodeOptio
pub_trajectory_ = create_publisher<Trajectory>("~/output/trajectory", 1);
pub_debug_markers_ =
create_publisher<visualization_msgs::msg::MarkerArray>("~/output/debug_markers", 1);
pub_runtime_ = create_publisher<std_msgs::msg::Int64>("~/output/runtime_microseconds", 1);
pub_runtime_ =
create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/output/runtime_microseconds", 1);

const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
vehicle_lateral_offset_ = static_cast<Float>(vehicle_info.max_lateral_offset_m);
Expand Down Expand Up @@ -223,7 +224,8 @@ void ObstacleVelocityLimiterNode::onTrajectory(const Trajectory::ConstSharedPtr

const auto t_end = std::chrono::system_clock::now();
const auto runtime = std::chrono::duration_cast<std::chrono::microseconds>(t_end - t_start);
pub_runtime_->publish(std_msgs::msg::Int64().set__data(runtime.count()));
pub_runtime_->publish(tier4_debug_msgs::msg::Float64Stamped().set__stamp(now()).set__data(
static_cast<double>(runtime.count())));

if (pub_debug_markers_->get_subscription_count() > 0) {
const auto safe_projected_linestrings =
Expand Down

0 comments on commit 2aa9d1c

Please sign in to comment.