rcmemulator.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import json
00003 import rospy
00004 from firos.srv import FIROS_Info, FIROS_InfoResponse
00005 
00006 
00007 def get_robot_info(req):
00008     ret = FIROS_InfoResponse()
00009     robot = {
00010         req.instance_name: {
00011             "topics": [
00012                 {
00013                     "name": "cmd_vel_mux/input/teleop",
00014                     "msg": "geometry_msgs/Twist",
00015                     "type": "publisher"
00016                 },
00017                 {
00018                     "name": "invented_topic_not_allowed",
00019                     "msg": "std_msgs/String",
00020                     "type": "publisher"
00021                 },
00022                 {
00023                     "name": "move_base/goal",
00024                     "msg": "move_base_msgs/MoveBaseActionGoal",
00025                     "type": "publisher"
00026                 },
00027                 {
00028                     "name": "move_base/result",
00029                     "msg": "move_base_msgs/MoveBaseActionResult",
00030                     "type": "subscriber"
00031                 }
00032             ]
00033         }
00034     }
00035     ret.json_format = json.dumps(robot)
00036     return ret
00037 
00038 
00039 if __name__ == "__main__":
00040     ROS_NODE = 'rcm_emulator'
00041     ROS_SERVICE = 'firos_info'
00042     print 'Node ' + ROS_NODE + ' up with service ' + ROS_SERVICE
00043     rospy.init_node(ROS_NODE)
00044     rospy.Service(ROS_SERVICE, FIROS_Info, get_robot_info)
00045     rospy.spin()


firos
Author(s): IƱigo Gonzalez, igonzalez@ikergune.com
autogenerated on Thu Jun 6 2019 17:51:04