send_destination_request.py 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  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 argparse
  17. import rclpy
  18. from rclpy.node import Node
  19. from rmf_fleet_msgs.msg import Location
  20. from rmf_fleet_msgs.msg import DestinationRequest
  21. def main(argv = sys.argv):
  22. '''
  23. Example destination request:
  24. - fleet_name: magni
  25. - robot_name: magni123
  26. - task_id: 6tyghb4edujrefyd
  27. - x: 0.0
  28. - y: 0.0
  29. - yaw: 0.0
  30. - level_name: B1
  31. '''
  32. default_fleet_name = 'fleet_name'
  33. default_robot_name = 'robot_name'
  34. default_task_id = '6tyghb4edujrefyd'
  35. default_desired_x = 0.0
  36. default_desired_y = 0.0
  37. default_desired_yaw = 0.0
  38. default_level_name = 'B1'
  39. default_topic_name = 'robot_destination_requests'
  40. parser = argparse.ArgumentParser()
  41. parser.add_argument('-f', '--fleet-name', default=default_fleet_name)
  42. parser.add_argument('-r', '--robot-name', default=default_robot_name)
  43. parser.add_argument('-x', default=default_desired_x)
  44. parser.add_argument('-y', default=default_desired_y)
  45. parser.add_argument('--yaw', default=default_desired_yaw)
  46. parser.add_argument('-l', '--level-name', default=default_level_name)
  47. parser.add_argument('-i', '--task-id', default=default_task_id)
  48. parser.add_argument('-t', '--topic-name', default=default_topic_name)
  49. args = parser.parse_args(argv[1:])
  50. print('fleet_name: {}'.format(args.fleet_name))
  51. print('robot_name: {}'.format(args.robot_name))
  52. print('x: {}'.format(args.x))
  53. print('y: {}'.format(args.y))
  54. print('yaw: {}'.format(args.yaw))
  55. print('level_name: {}'.format(args.level_name))
  56. print('task_id: {}'.format(args.task_id))
  57. print('topic_name: {}'.format(args.topic_name))
  58. rclpy.init()
  59. node = rclpy.create_node('send_destination_request_node')
  60. pub = node.create_publisher(DestinationRequest, args.topic_name, 10)
  61. msg = DestinationRequest()
  62. msg.fleet_name = args.fleet_name
  63. msg.robot_name = args.robot_name
  64. msg.task_id = args.task_id
  65. # ignore time for now
  66. msg.destination.x = float(args.x)
  67. msg.destination.y = float(args.y)
  68. msg.destination.yaw = float(args.yaw)
  69. msg.destination.level_name = args.level_name
  70. rclpy.spin_once(node, timeout_sec=1.0)
  71. pub.publish(msg)
  72. rclpy.spin_once(node, timeout_sec=0.5)
  73. print('all done!')
  74. if __name__ == '__main__':
  75. main(sys.argv)