|
| 1 | +#! /usr/bin/env python3 |
| 2 | +# -*- coding: utf-8 -*- |
| 3 | + |
| 4 | +# Copyright 2024 TIER IV, Inc. All rights reserved. |
| 5 | +# |
| 6 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 7 | +# you may not use this file except in compliance with the License. |
| 8 | +# You may obtain a copy of the License at |
| 9 | +# |
| 10 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 11 | +# |
| 12 | +# Unless required by applicable law or agreed to in writing, software |
| 13 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 14 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 15 | +# See the License for the specific language governing permissions and |
| 16 | +# limitations under the License. |
| 17 | + |
| 18 | +import argparse |
| 19 | + |
| 20 | +from autoware_adapi_v1_msgs.msg import RouteOption |
| 21 | +from autoware_adapi_v1_msgs.msg import RoutePrimitive |
| 22 | +from autoware_adapi_v1_msgs.msg import RouteSegment |
| 23 | +from autoware_adapi_v1_msgs.srv import SetRoute |
| 24 | +from geometry_msgs.msg import Pose |
| 25 | +import rclpy |
| 26 | +from rclpy.node import Node |
| 27 | +from std_msgs.msg import Header |
| 28 | +import yaml |
| 29 | + |
| 30 | + |
| 31 | +class route_client(Node): |
| 32 | + def __init__(self): |
| 33 | + super().__init__("route_client") |
| 34 | + self.cli = self.create_client(SetRoute, "/api/routing/change_route") |
| 35 | + |
| 36 | + while not self.cli.wait_for_service(timeout_sec=1.0): |
| 37 | + self.get_logger().info("service not available...") |
| 38 | + |
| 39 | + self.req = SetRoute.Request() |
| 40 | + |
| 41 | + def send_request(self, filepath): |
| 42 | + self.req.header = Header() |
| 43 | + self.req.header.frame_id = "map" |
| 44 | + self.req.header.stamp = self.get_clock().now().to_msg() |
| 45 | + self.req.option = RouteOption() |
| 46 | + self.req.option.allow_goal_modification = True |
| 47 | + |
| 48 | + with open(filepath) as file: |
| 49 | + data = yaml.safe_load(file) |
| 50 | + self.req.goal = self.set_goal(data["goal"]) |
| 51 | + self.req.segments = self.set_segments(data["segments"]) |
| 52 | + self.future = self.cli.call_async(self.req) |
| 53 | + |
| 54 | + def set_goal(self, goal): |
| 55 | + out = Pose() |
| 56 | + out.position.x = goal["position"]["x"] |
| 57 | + out.position.y = goal["position"]["y"] |
| 58 | + out.position.z = goal["position"]["z"] |
| 59 | + out.orientation.x = goal["orientation"]["x"] |
| 60 | + out.orientation.y = goal["orientation"]["y"] |
| 61 | + out.orientation.z = goal["orientation"]["z"] |
| 62 | + out.orientation.w = goal["orientation"]["w"] |
| 63 | + |
| 64 | + return out |
| 65 | + |
| 66 | + def set_segments(self, segments): |
| 67 | + out = [] |
| 68 | + for segment in segments: |
| 69 | + out_segment = RouteSegment() |
| 70 | + out_segment.preferred.id = segment["preferred"]["id"] |
| 71 | + out_segment.preferred.type = segment["preferred"]["type"] |
| 72 | + for alt in segment["alternatives"]: |
| 73 | + out_alt = RoutePrimitive() |
| 74 | + out_alt.id = alt["id"] |
| 75 | + out_alt.type = alt["type"] |
| 76 | + out_segment.alternatives.append(out_alt) |
| 77 | + |
| 78 | + out.append(out_segment) |
| 79 | + return out |
| 80 | + |
| 81 | + |
| 82 | +def main(args=None): |
| 83 | + rclpy.init(args=args) |
| 84 | + |
| 85 | + parser = argparse.ArgumentParser(description="Send set route request.") |
| 86 | + parser.add_argument("filepath", type=str, help="path to yaml file containing route information") |
| 87 | + args = parser.parse_args() |
| 88 | + |
| 89 | + client = route_client() |
| 90 | + client.send_request(args.filepath) |
| 91 | + |
| 92 | + while rclpy.ok(): |
| 93 | + rclpy.spin_once(client) |
| 94 | + if client.future.done(): |
| 95 | + try: |
| 96 | + client.get_logger().info("Service requested.") |
| 97 | + except Exception as e: |
| 98 | + client.get_logger().info("Error: %r" % (e,)) |
| 99 | + break |
| 100 | + |
| 101 | + client.destroy_node() |
| 102 | + |
| 103 | + rclpy.shutdown() |
| 104 | + |
| 105 | + |
| 106 | +if __name__ == "__main__": |
| 107 | + main() |
0 commit comments