setpoint.py
Go to the documentation of this file.
1 # -*- coding: utf-8 -*-
2 # vim:set ts=4 sw=4 et:
3 #
4 # Copyright 2015 Vladimir Ermakov.
5 #
6 # This file is part of the mavros package and subject to the license terms
7 # in the top-level LICENSE file of the mavros repository.
8 # https://github.com/mavlink/mavros/tree/master/LICENSE.md
9 
10 import rospy
11 import mavros
12 
13 from std_msgs.msg import Header, Float64
14 from geometry_msgs.msg import TwistStamped, PoseStamped, PoseWithCovarianceStamped, \
15  Vector3, Vector3Stamped, Point, Quaternion
16 
17 
18 def get_pub_accel_accel(**kvargs):
19  """
20  Returns publisher for :setpoint_accel: plugin, :accel: topic
21  """
22  return rospy.Publisher(mavros.get_topic('setpoint_accel', 'accel'), Vector3Stamped, **kvargs)
23 
24 
26  """
27  Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic
28  """
29  return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'cmd_vel'), PoseStamped, **kvargs)
30 
31 
33  """
34  Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic
35  """
36  return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'att_throttle'), Float64, **kvargs)
37 
38 
39 def get_pub_attitude_pose(**kvargs):
40  """
41  Returns publisher for :setpoint_attitude: plugin, :attituse: topic
42  """
43  return rospy.Publisher(mavros.get_topic('setpoint_attitude', 'attitude'), PoseStamped, **kvargs)
44 
45 
47  """
48  Returns publisher for :setpoint_attitude: plugin, :attituse: topic (with covariance)
49  """
50  raise DeprecationWarning("PoseWithCovarianceStamped subscriber removed.")
51 
52 
53 def get_pub_position_local(**kvargs):
54  """
55  Returns publisher for :setpoint_position: plugin, :local: topic
56  """
57  return rospy.Publisher(mavros.get_topic('setpoint_position', 'local'), PoseStamped, **kvargs)
58 
59 
61  """
62  Returns publisher for :setpoint_velocity: plugin, :cmd_vel: topic
63  """
64  return rospy.Publisher(mavros.get_topic('setpoint_velocity', 'cmd_vel'), TwistStamped, **kvargs)
65 
66 
def get_pub_accel_accel(kvargs)
Definition: setpoint.py:18
def get_topic(args)
Definition: __init__.py:49
def get_pub_attitude_cmd_vel(kvargs)
Definition: setpoint.py:25
def get_pub_velocity_cmd_vel(kvargs)
Definition: setpoint.py:60
def get_pub_attitude_throttle(kvargs)
Definition: setpoint.py:32
def get_pub_attitude_posecov(kvargs)
Definition: setpoint.py:46
def get_pub_position_local(kvargs)
Definition: setpoint.py:53
def get_pub_attitude_pose(kvargs)
Definition: setpoint.py:39


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11