send_path_request.py 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  1. #!/usr/bin/env python3
  2. # Copyright 2019 Open Source Robotics Foundation, Inc.
  3. #
  4. # Licensed under the Apache License, Version 2.0 (the "License");
  5. # you may not use this file except in compliance with the License.
  6. # You may obtain a copy of the License at
  7. #
  8. # http://www.apache.org/licenses/LICENSE-2.0
  9. #
  10. # Unless required by applicable law or agreed to in writing, software
  11. # distributed under the License is distributed on an "AS IS" BASIS,
  12. # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. # See the License for the specific language governing permissions and
  14. # limitations under the License.
  15. import sys
  16. import json
  17. import argparse
  18. import rclpy
  19. from rclpy.node import Node
  20. from rmf_fleet_msgs.msg import Location
  21. from rmf_fleet_msgs.msg import PathRequest
  22. def print_path(json_path_string):
  23. path_dict = json.loads(json_path_string)
  24. for waypoint in path_dict:
  25. print('01 x: {} y: {} yaw: {} level_name: {}'.format(
  26. waypoint['x'], waypoint['y'], waypoint['yaw'],
  27. waypoint['level_name']))
  28. def get_path_message(json_path_string):
  29. path_dict = json.loads(json_path_string)
  30. path = []
  31. for waypoint in path_dict:
  32. new_wp = Location()
  33. # ignore time for now
  34. new_wp.x = float(waypoint['x'])
  35. new_wp.y = float(waypoint['y'])
  36. new_wp.yaw = float(waypoint['yaw'])
  37. new_wp.level_name = waypoint['level_name']
  38. path.append(new_wp)
  39. return path
  40. def main(argv = sys.argv):
  41. '''
  42. Example path request:
  43. - fleet_name: magni
  44. - robot_name: magni123
  45. - task_id: tfuhbjndsujewsduisd
  46. - path: [
  47. {"x": 0.0, "y": 0.0, "yaw": 0.0, "level_name": "B1"},
  48. {"x": 1.0, "y": 1.0, "yaw": 1.0, "level_name": "B1"},
  49. {"x": 2.0, "y": 2.0, "yaw": 2.0, "level_name": "B1"}]
  50. '''
  51. default_fleet_name = 'fleet_name'
  52. default_robot_name = 'robot_name'
  53. default_task_id = 'tfuhbjndsujewsduisd'
  54. default_desired_path = '[]'
  55. default_topic_name = 'robot_path_requests'
  56. parser = argparse.ArgumentParser()
  57. parser.add_argument('-f', '--fleet-name', default=default_fleet_name)
  58. parser.add_argument('-r', '--robot-name', default=default_robot_name)
  59. parser.add_argument('-i', '--task-id', default=default_task_id)
  60. parser.add_argument('-p', '--path', default=default_desired_path)
  61. parser.add_argument('-t', '--topic-name', default=default_topic_name)
  62. args = parser.parse_args(argv[1:])
  63. print('fleet_name: {}'.format(args.fleet_name))
  64. print('robot_name: {}'.format(args.robot_name))
  65. print('task_id: {}'.format(args.task_id))
  66. print_path(args.path)
  67. print('topic_name: {}'.format(args.topic_name))
  68. rclpy.init()
  69. node = rclpy.create_node('send_path_request_node')
  70. pub = node.create_publisher(PathRequest, args.topic_name, 10)
  71. msg = PathRequest()
  72. msg.fleet_name = args.fleet_name
  73. msg.robot_name = args.robot_name
  74. msg.task_id = args.task_id
  75. msg.path = get_path_message(args.path)
  76. rclpy.spin_once(node, timeout_sec=2.0)
  77. pub.publish(msg)
  78. rclpy.spin_once(node, timeout_sec=0.5)
  79. print('all done!')
  80. if __name__ == '__main__':
  81. main(sys.argv)