Skip to content

Commit 3cb712c

Browse files
author
Ahmed Ebrahim
committed
feat(reroute-static-obstacle): fixing compilation issue after api changes for changing and setting route
NOTE : this is still wip and the functionality is not yet finished after this change. Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>
1 parent 9988eab commit 3cb712c

File tree

2 files changed

+18
-14
lines changed

2 files changed

+18
-14
lines changed

planning/mission_planner/src/rerouting_static_obstacle/rerouting_static_obstacle.cpp

+12-10
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ ReroutingStaticObstacle::ReroutingStaticObstacle(const rclcpp::NodeOptions & nod
4444
std::bind(&ReroutingStaticObstacle::on_trigger, this, _1));
4545

4646
const auto adaptor = component_interface_utils::NodeAdaptor(this);
47-
adaptor.init_cli(cli_change_route_);
47+
adaptor.init_cli(cli_set_lanelet_route_);
4848
}
4949

5050
void ReroutingStaticObstacle::on_odom(const nav_msgs::msg::Odometry::SharedPtr msg)
@@ -95,7 +95,7 @@ void ReroutingStaticObstacle::on_trigger(const geometry_msgs::msg::PointStamped:
9595
search_alternative_route(selected_point_lanelet, alternative_route_lanelets);
9696

9797
if (alternative_route_found) {
98-
change_route(alternative_route_lanelets);
98+
set_lanelet_route(alternative_route_lanelets);
9999
}
100100
}
101101
}
@@ -175,24 +175,26 @@ bool ReroutingStaticObstacle::search_alternative_route(
175175
return alternative_route_found;
176176
}
177177

178-
void ReroutingStaticObstacle::change_route(const lanelet::routing::LaneletPath & lanelet_path)
178+
void ReroutingStaticObstacle::set_lanelet_route(const lanelet::routing::LaneletPath & lanelet_path)
179179
{
180-
const auto req = std::make_shared<ChangeRoute::Service::Request>();
180+
const auto req = std::make_shared<SetLaneletRoute::Service::Request>();
181181
req->header.frame_id = "map";
182182
req->header.stamp = this->get_clock()->now();
183-
req->goal = goal_pose_;
183+
req->goal_pose = goal_pose_;
184184
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);
186186
}
187187

188188
void ReroutingStaticObstacle::convert_lanelet_path_to_route_segments(
189189
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
191191
{
192192
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);
196198
route_segments.push_back(route_segment);
197199
}
198200
}

planning/mission_planner/src/rerouting_static_obstacle/rerouting_static_obstacle.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@
3232
#include <lanelet2_routing/Route.h>
3333
#include <lanelet2_routing/RoutingGraph.h>
3434
#include <lanelet2_traffic_rules/TrafficRules.h>
35+
#include <autoware_adapi_v1_msgs/msg/route_segment.hpp>
36+
3537

3638
#include <vector>
3739

@@ -40,7 +42,7 @@ namespace mission_planner
4042
using autoware_auto_mapping_msgs::msg::HADMapBin;
4143
class ReroutingStaticObstacle : public rclcpp::Node
4244
{
43-
using ChangeRoute = planning_interface::ChangeRoute;
45+
using SetLaneletRoute = planning_interface::SetLaneletRoute;
4446

4547
public:
4648
explicit ReroutingStaticObstacle(const rclcpp::NodeOptions & node_options);
@@ -50,7 +52,7 @@ class ReroutingStaticObstacle : public rclcpp::Node
5052
rclcpp::Subscription<geometry_msgs::msg::PointStamped>::SharedPtr sub_trigger_;
5153
rclcpp::Subscription<autoware_planning_msgs::msg::LaneletRoute>::SharedPtr sub_route_;
5254
rclcpp::Subscription<HADMapBin>::SharedPtr map_subscriber_;
53-
component_interface_utils::Client<ChangeRoute>::SharedPtr cli_change_route_;
55+
component_interface_utils::Client<SetLaneletRoute>::SharedPtr cli_set_lanelet_route_;
5456

5557
lanelet::LaneletMapPtr lanelet_map_ptr_;
5658
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;
@@ -76,11 +78,11 @@ class ReroutingStaticObstacle : public rclcpp::Node
7678
const lanelet::ConstLanelet & selected_point_lanelet,
7779
lanelet::routing::LaneletPath & alternative_route_lanelets) const;
7880

79-
void change_route(const lanelet::routing::LaneletPath & lanelet_path);
81+
void set_lanelet_route(const lanelet::routing::LaneletPath & lanelet_path);
8082

8183
void convert_lanelet_path_to_route_segments(
8284
const lanelet::routing::LaneletPath & lanelet_path,
83-
std::vector<autoware_adapi_v1_msgs::msg::RouteSegment> & route_segments) const;
85+
std::vector<autoware_planning_msgs::msg::LaneletSegment> & route_segments) const;
8486
};
8587

8688
} // namespace mission_planner

0 commit comments

Comments
 (0)