Skip to content

Commit 307d698

Browse files
committed
fix(motion_velocity_planner): remove velocity factor
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 0845563 commit 307d698

File tree

5 files changed

+4
-20
lines changed

5 files changed

+4
-20
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@
1919
#include "velocity_planning_result.hpp"
2020

2121
#include <autoware/motion_utils/factor/planning_factor_interface.hpp>
22-
#include <autoware/motion_utils/factor/velocity_factor_interface.hpp>
2322
#include <autoware/universe_utils/ros/processing_time_publisher.hpp>
2423
#include <rclcpp/rclcpp.hpp>
2524

@@ -47,7 +46,6 @@ class PluginModuleInterface
4746
const std::shared_ptr<const PlannerData> planner_data) = 0;
4847
virtual std::string get_module_name() const = 0;
4948
virtual void publish_planning_factor() {}
50-
autoware::motion_utils::VelocityFactorInterface velocity_factor_interface_;
5149
rclcpp::Logger logger_ = rclcpp::get_logger("");
5250
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_publisher_;
5351
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr virtual_wall_publisher_;

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717

1818
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
1919

20-
#include <autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
2120
#include <geometry_msgs/msg/point.hpp>
2221
#include <visualization_msgs/msg/marker_array.hpp>
2322

@@ -43,7 +42,6 @@ struct VelocityPlanningResult
4342
{
4443
std::vector<geometry_msgs::msg::Point> stop_points{};
4544
std::vector<SlowdownInterval> slowdown_intervals{};
46-
std::optional<autoware_adapi_v1_msgs::msg::VelocityFactor> velocity_factor{};
4745
};
4846
} // namespace autoware::motion_velocity_planner
4947

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,10 @@ This means that to stop before a wall, a stop point is inserted in the trajector
3030

3131
## Output topics
3232

33-
| Name | Type | Description |
34-
| --------------------------- | ------------------------------------------------- | -------------------------------------------------- |
35-
| `~/output/trajectory` | autoware_planning_msgs::msg::Trajectory | Ego trajectory with updated velocity profile |
36-
| `~/output/velocity_factors` | autoware_adapi_v1_msgs::msg::VelocityFactorsArray | factors causing change in the ego velocity profile |
33+
| Name | Type | Description |
34+
| ----------------------------------------- | ---------------------------------------------- | -------------------------------------------------- |
35+
| `~/output/trajectory` | autoware_planning_msgs::msg::Trajectory | Ego trajectory with updated velocity profile |
36+
| `~/output/planning_factors/<MODULE_NAME>` | tier4_planning_msgs::msg::PlanningFactorsArray | factors causing change in the ego velocity profile |
3737

3838
## Services
3939

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -82,9 +82,6 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions &
8282
// Publishers
8383
trajectory_pub_ =
8484
this->create_publisher<autoware_planning_msgs::msg::Trajectory>("~/output/trajectory", 1);
85-
velocity_factor_publisher_ =
86-
this->create_publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
87-
"~/output/velocity_factors", 1);
8885
processing_time_publisher_ =
8986
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
9087
debug_viz_pub_ =
@@ -425,20 +422,13 @@ autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_traj
425422
resampled_trajectory, std::make_shared<const PlannerData>(planner_data_));
426423
processing_times["plan_velocities"] = stop_watch.toc("plan_velocities");
427424

428-
autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factors;
429-
velocity_factors.header.frame_id = "map";
430-
velocity_factors.header.stamp = get_clock()->now();
431-
432425
for (const auto & planning_result : planning_results) {
433426
for (const auto & stop_point : planning_result.stop_points)
434427
insert_stop(output_trajectory_msg, stop_point);
435428
for (const auto & slowdown_interval : planning_result.slowdown_intervals)
436429
insert_slowdown(output_trajectory_msg, slowdown_interval);
437-
if (planning_result.velocity_factor)
438-
velocity_factors.factors.push_back(*planning_result.velocity_factor);
439430
}
440431

441-
velocity_factor_publisher_->publish(velocity_factors);
442432
return output_trajectory_msg;
443433
}
444434

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -93,8 +93,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node
9393
// publishers
9494
rclcpp::Publisher<autoware_planning_msgs::msg::Trajectory>::SharedPtr trajectory_pub_;
9595
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_viz_pub_;
96-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>::SharedPtr
97-
velocity_factor_publisher_;
9896
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{
9997
this, "~/debug/processing_time_ms_diag"};
10098
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;

0 commit comments

Comments
 (0)