diff --git a/planning/obstacle_velocity_limiter/README.md b/planning/obstacle_velocity_limiter/README.md index 5f833135e1ae4..6ca33b4913b12 100644 --- a/planning/obstacle_velocity_limiter/README.md +++ b/planning/obstacle_velocity_limiter/README.md @@ -152,11 +152,11 @@ For example a value of `1` means all trajectory points will be evaluated while a ### Outputs -| Name | Type | Description | -| ------------------------ | ---------------------------------------- | -------------------------------------------------------- | -| `~/output/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Trajectory with adjusted velocities | -| `~/output/debug_markers` | `visualization_msgs/MarkerArray` | Debug markers (envelopes, obstacle polygons) | -| `~/output/runtime_us` | `std_msgs/Int64` | Time taken to calculate the trajectory (in microseconds) | +| Name | Type | Description | +| ------------------------------- | ---------------------------------------- | -------------------------------------------------------- | +| `~/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) | ## Parameters diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp index 47560a771af7d..584d6eb42e712 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp @@ -90,6 +90,7 @@ class ObstacleVelocityLimiterNode : public rclcpp::Node /// @brief callback for parameter updates /// @param[in] parameters updated parameters and their new values + /// @return result of parameter update rcl_interfaces::msg::SetParametersResult onParameter( const std::vector & parameters); diff --git a/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml b/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml index 4c00bfebe3210..b3cd39eb709db 100644 --- a/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml +++ b/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml @@ -6,28 +6,19 @@ - - + + - - - - - - - - - - + - + diff --git a/planning/obstacle_velocity_limiter/src/forward_projection.cpp b/planning/obstacle_velocity_limiter/src/forward_projection.cpp index 2718ab6de6dd9..ecd633e6ba6de 100644 --- a/planning/obstacle_velocity_limiter/src/forward_projection.cpp +++ b/planning/obstacle_velocity_limiter/src/forward_projection.cpp @@ -63,7 +63,6 @@ linestring_t bicycleProjectionLine( const geometry_msgs::msg::Point & origin, const ProjectionParameters & params, const double steering_angle) { - // TODO(Maxime CLEMENT): use Eigen for faster calculation linestring_t line; line.reserve(params.points_per_projection); line.emplace_back(origin.x, origin.y);