Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 __all__ = (
00011 'long',
00012 'int',
00013 'arming',
00014 'set_home',
00015 'takeoff',
00016 'land',
00017 'trigger_control',
00018 )
00019
00020 import rospy
00021 import mavros
00022
00023 from mavros_msgs.srv import CommandLong, CommandInt, CommandBool, CommandHome, CommandTOL, CommandTriggerControl
00024
00025
00026 def _get_proxy(service, type):
00027 return rospy.ServiceProxy(mavros.get_topic('cmd', service), type)
00028
00029
00030 long = None
00031 int = None
00032 arming = None
00033 set_home = None
00034 takeoff = None
00035 land = None
00036 trigger_control = None
00037
00038
00039 def _setup_services():
00040 global long, int, arming, set_home, takeoff, land, trigger_control
00041 long = _get_proxy('command', CommandLong)
00042 int = _get_proxy('command_int', CommandInt)
00043 arming = _get_proxy('arming', CommandBool)
00044 set_home = _get_proxy('set_home', CommandHome)
00045 takeoff = _get_proxy('takeoff', CommandTOL)
00046 land = _get_proxy('land', CommandTOL)
00047 trigger_control = _get_proxy('trigger_control', CommandTriggerControl)
00048
00049
00050
00051 mavros.register_on_namespace_update(_setup_services)