18
18
#include < autoware/behavior_velocity_planner_common/planner_data.hpp>
19
19
#include < autoware/behavior_velocity_planner_common/utilization/util.hpp>
20
20
#include < autoware/motion_utils/factor/planning_factor_interface.hpp>
21
- #include < autoware/motion_utils/factor/velocity_factor_interface.hpp>
22
21
#include < autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
23
22
#include < autoware/motion_utils/trajectory/trajectory.hpp>
24
23
#include < autoware/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp>
28
27
#include < autoware/universe_utils/system/time_keeper.hpp>
29
28
#include < builtin_interfaces/msg/time.hpp>
30
29
31
- #include < autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
32
- #include < autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
33
30
#include < autoware_internal_debug_msgs/msg/float64_stamped.hpp>
34
31
#include < autoware_planning_msgs/msg/path.hpp>
35
32
#include < tier4_planning_msgs/msg/path_with_lane_id.hpp>
51
48
namespace autoware ::behavior_velocity_planner
52
49
{
53
50
54
- using autoware::motion_utils::PlanningBehavior;
55
- using autoware::motion_utils::VelocityFactor;
56
51
using autoware::objects_of_interest_marker_interface::ColorName;
57
52
using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface;
58
53
using autoware::universe_utils::DebugPublisher;
@@ -97,8 +92,6 @@ class SceneModuleInterface
97
92
planner_data_ = planner_data;
98
93
}
99
94
100
- void resetVelocityFactor () { velocity_factor_.reset (); }
101
- VelocityFactor getVelocityFactor () const { return velocity_factor_.get (); }
102
95
std::vector<ObjectOfInterest> getObjectsOfInterestData () const { return objects_of_interest_; }
103
96
void clearObjectsOfInterestData () { objects_of_interest_.clear (); }
104
97
@@ -107,7 +100,6 @@ class SceneModuleInterface
107
100
rclcpp::Logger logger_;
108
101
rclcpp::Clock::SharedPtr clock_;
109
102
std::shared_ptr<const PlannerData> planner_data_;
110
- autoware::motion_utils::VelocityFactorInterface velocity_factor_; // TODO(soblin): remove this
111
103
std::vector<ObjectOfInterest> objects_of_interest_;
112
104
mutable std::shared_ptr<universe_utils::TimeKeeper> time_keeper_;
113
105
std::shared_ptr<motion_utils::PlanningFactorInterface> planning_factor_interface_;
@@ -143,8 +135,6 @@ class SceneModuleManagerInterface
143
135
}
144
136
pub_virtual_wall_ = node.create_publisher <visualization_msgs::msg::MarkerArray>(
145
137
std::string (" ~/virtual_wall/" ) + module_name, 5 );
146
- pub_velocity_factor_ = node.create_publisher <autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
147
- std::string (" /planning/velocity_factors/" ) + module_name, 1 );
148
138
planning_factor_interface_ =
149
139
std::make_shared<motion_utils::PlanningFactorInterface>(&node, module_name);
150
140
@@ -180,21 +170,12 @@ class SceneModuleManagerInterface
180
170
StopWatch<std::chrono::milliseconds> stop_watch;
181
171
stop_watch.tic (" Total" );
182
172
visualization_msgs::msg::MarkerArray debug_marker_array;
183
- autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array;
184
- velocity_factor_array.header .frame_id = " map" ;
185
- velocity_factor_array.header .stamp = clock_->now ();
186
173
187
174
for (const auto & scene_module : scene_modules_) {
188
- scene_module->resetVelocityFactor ();
189
175
scene_module->setPlannerData (planner_data_);
190
176
scene_module->modifyPathVelocity (path);
191
177
192
178
// The velocity factor must be called after modifyPathVelocity.
193
- // TODO(soblin): remove this
194
- const auto velocity_factor = scene_module->getVelocityFactor ();
195
- if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) {
196
- velocity_factor_array.factors .emplace_back (velocity_factor);
197
- }
198
179
199
180
for (const auto & marker : scene_module->createDebugMarkerArray ().markers ) {
200
181
debug_marker_array.markers .push_back (marker);
@@ -203,7 +184,6 @@ class SceneModuleManagerInterface
203
184
virtual_wall_marker_creator_.add_virtual_walls (scene_module->createVirtualWalls ());
204
185
}
205
186
206
- pub_velocity_factor_->publish (velocity_factor_array);
207
187
planning_factor_interface_->publish ();
208
188
pub_debug_->publish (debug_marker_array);
209
189
if (is_publish_debug_path_) {
@@ -274,8 +254,6 @@ class SceneModuleManagerInterface
274
254
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_virtual_wall_;
275
255
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_debug_;
276
256
rclcpp::Publisher<tier4_planning_msgs::msg::PathWithLaneId>::SharedPtr pub_debug_path_;
277
- rclcpp::Publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>::SharedPtr
278
- pub_velocity_factor_;
279
257
280
258
std::shared_ptr<DebugPublisher> processing_time_publisher_;
281
259
0 commit comments