@@ -44,7 +44,7 @@ ReroutingStaticObstacle::ReroutingStaticObstacle(const rclcpp::NodeOptions & nod
44
44
std::bind (&ReroutingStaticObstacle::on_trigger, this , _1));
45
45
46
46
const auto adaptor = component_interface_utils::NodeAdaptor (this );
47
- adaptor.init_cli (cli_change_route_ );
47
+ adaptor.init_cli (cli_set_lanelet_route_ );
48
48
}
49
49
50
50
void ReroutingStaticObstacle::on_odom (const nav_msgs::msg::Odometry::SharedPtr msg)
@@ -95,7 +95,7 @@ void ReroutingStaticObstacle::on_trigger(const geometry_msgs::msg::PointStamped:
95
95
search_alternative_route (selected_point_lanelet, alternative_route_lanelets);
96
96
97
97
if (alternative_route_found) {
98
- change_route (alternative_route_lanelets);
98
+ set_lanelet_route (alternative_route_lanelets);
99
99
}
100
100
}
101
101
}
@@ -175,24 +175,26 @@ bool ReroutingStaticObstacle::search_alternative_route(
175
175
return alternative_route_found;
176
176
}
177
177
178
- void ReroutingStaticObstacle::change_route (const lanelet::routing::LaneletPath & lanelet_path)
178
+ void ReroutingStaticObstacle::set_lanelet_route (const lanelet::routing::LaneletPath & lanelet_path)
179
179
{
180
- const auto req = std::make_shared<ChangeRoute ::Service::Request>();
180
+ const auto req = std::make_shared<SetLaneletRoute ::Service::Request>();
181
181
req->header .frame_id = " map" ;
182
182
req->header .stamp = this ->get_clock ()->now ();
183
- req->goal = goal_pose_;
183
+ req->goal_pose = goal_pose_;
184
184
convert_lanelet_path_to_route_segments (lanelet_path, req->segments );
185
- cli_change_route_ ->async_send_request (req);
185
+ cli_set_lanelet_route_ ->async_send_request (req);
186
186
}
187
187
188
188
void ReroutingStaticObstacle::convert_lanelet_path_to_route_segments (
189
189
const lanelet::routing::LaneletPath & lanelet_path,
190
- std::vector<autoware_adapi_v1_msgs ::msg::RouteSegment > & route_segments) const
190
+ std::vector<autoware_planning_msgs ::msg::LaneletSegment > & route_segments) const
191
191
{
192
192
for (const auto & ll : lanelet_path) {
193
- autoware_adapi_v1_msgs::msg::RouteSegment route_segment;
194
- route_segment.preferred .id = ll.id ();
195
- route_segment.preferred .type = " lane" ;
193
+ autoware_planning_msgs::msg::LaneletSegment route_segment;
194
+ autoware_planning_msgs::msg::LaneletPrimitive lanelet_primitive;
195
+ lanelet_primitive.id = ll.id ();
196
+ lanelet_primitive.primitive_type = " lane" ;
197
+ route_segment.primitives .push_back (lanelet_primitive);
196
198
route_segments.push_back (route_segment);
197
199
}
198
200
}
0 commit comments