send_mode_request.py 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  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 RobotMode
  20. from rmf_fleet_msgs.msg import ModeRequest
  21. def main(argv = sys.argv):
  22. '''
  23. Example mode request:
  24. - fleet_name: magni
  25. - robot_name: magni123
  26. - task_id: 576y13ewgyffeijuais
  27. - mode.mode: PAUSED
  28. '''
  29. default_fleet_name = 'fleet_name'
  30. default_robot_name = 'robot_name'
  31. default_task_id = '576y13ewgyffeijuais'
  32. default_mode = 'mode'
  33. default_topic_name = 'robot_mode_requests'
  34. parser = argparse.ArgumentParser()
  35. parser.add_argument('-f', '--fleet-name', default=default_fleet_name)
  36. parser.add_argument('-r', '--robot-name', default=default_robot_name)
  37. parser.add_argument('-m', '--mode', default=default_mode)
  38. parser.add_argument('-i', '--task-id', default=default_task_id)
  39. parser.add_argument('-t', '--topic-name', default=default_topic_name)
  40. args = parser.parse_args(argv[1:])
  41. print('fleet_name: {}'.format(args.fleet_name))
  42. print('robot_name: {}'.format(args.robot_name))
  43. print('mode: {}'.format(args.mode))
  44. print('task_id: {}'.format(args.task_id))
  45. print('topic_name: {}'.format(args.topic_name))
  46. rclpy.init()
  47. node = rclpy.create_node('send_mode_request_node')
  48. pub = node.create_publisher(ModeRequest, args.topic_name, 10)
  49. msg = ModeRequest()
  50. msg.fleet_name = args.fleet_name
  51. msg.robot_name = args.robot_name
  52. msg.task_id = args.task_id
  53. if args.mode == 'mode':
  54. print('Please insert desired mode, pause or resume')
  55. return
  56. elif args.mode == 'pause':
  57. msg.mode.mode = RobotMode.MODE_PAUSED
  58. elif args.mode == 'resume':
  59. msg.mode.mode = RobotMode.MODE_MOVING
  60. else:
  61. print('unrecognized mode requested, only use pause or resume please')
  62. return
  63. rclpy.spin_once(node, timeout_sec=1.0)
  64. pub.publish(msg)
  65. rclpy.spin_once(node, timeout_sec=0.5)
  66. print('all done!')
  67. rclpy.shutdown()
  68. if __name__ == '__main__':
  69. main(sys.argv)