setpoint.py
Go to the documentation of this file.
00001 # -*- coding: utf-8 -*-
00002 # vim:set ts=4 sw=4 et:
00003 #
00004 # Copyright 2015 Vladimir Ermakov.
00005 #
00006 # This file is part of the mavros package and subject to the license terms
00007 # in the top-level LICENSE file of the mavros repository.
00008 # https://github.com/mavlink/mavros/tree/master/LICENSE.md
00009 
00010 import rospy
00011 import mavros
00012 
00013 from std_msgs.msg import Header, Float64
00014 from geometry_msgs.msg import TwistStamped, PoseStamped, PoseWithCovarianceStamped, \
00015         Vector3, Vector3Stamped, Point, Quaternion
00016 
00017 
00018 def get_pub_accel_accel(**kvargs):
00019     """
00020     Returns publisher for :setpoint_accel: plugin, :accel: topic
00021     """
00022     return rospy.Publisher(mavros.get_topic('setpoint_accel', 'accel'), Vector3Stamped, **kvargs)
00023 
00024 
00025 def get_pub_attitude_cmd_vel(**kvargs):
00026     """
00027     Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic
00028     """
00029     return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'cmd_vel'), PoseStamped, **kvargs)
00030 
00031 
00032 def get_pub_attitude_throttle(**kvargs):
00033     """
00034     Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic
00035     """
00036     return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'att_throttle'), Float64, **kvargs)
00037 
00038 
00039 def get_pub_attitude_pose(**kvargs):
00040     """
00041     Returns publisher for :setpoint_attitude: plugin, :attituse: topic
00042     """
00043     return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'attitude'), PoseStamped, **kvargs)
00044 
00045 
00046 def get_pub_attitude_posecov(**kvargs):
00047     """
00048     Returns publisher for :setpoint_attitude: plugin, :attituse: topic (with covariance)
00049     """
00050     raise DeprecationWarning("PoseWithCovarianceStamped subscriber removed.")
00051 
00052 
00053 def get_pub_position_local(**kvargs):
00054     """
00055     Returns publisher for :setpoint_position: plugin, :local: topic
00056     """
00057     return rospy.Publisher(mavros.get_topic('setpoint_position', 'local'), PoseStamped, **kvargs)
00058 
00059 
00060 def get_pub_velocity_cmd_vel(**kvargs):
00061     """
00062     Returns publisher for :setpoint_velocity: plugin, :cmd_vel: topic
00063     """
00064     return rospy.Publisher(mavros.get_topic('setpoint_velocity', 'cmd_vel'), TwistStamped, **kvargs)
00065 
00066 


mavros
Author(s): Vladimir Ermakov
autogenerated on Thu Feb 9 2017 04:00:17