13 from std_msgs.msg
import Header, Float64
14 from geometry_msgs.msg
import TwistStamped, PoseStamped, PoseWithCovarianceStamped, \
15 Vector3, Vector3Stamped, Point, Quaternion
20 Returns publisher for :setpoint_accel: plugin, :accel: topic 22 return rospy.Publisher(
mavros.get_topic(
'setpoint_accel',
'accel'), Vector3Stamped, **kvargs)
27 Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic 29 return rospy.Publisher(
mavros.get_topic(
'setpoint_attitude',
'cmd_vel'), PoseStamped, **kvargs)
34 Returns publisher for :setpoint_attitude: plugin, :cmd_vel: topic 36 return rospy.Publisher(
mavros.get_topic(
'setpoint_attitude',
'att_throttle'), Float64, **kvargs)
41 Returns publisher for :setpoint_attitude: plugin, :attituse: topic 43 return rospy.Publisher(
mavros.get_topic(
'setpoint_attitude',
'attitude'), PoseStamped, **kvargs)
48 Returns publisher for :setpoint_attitude: plugin, :attituse: topic (with covariance) 50 raise DeprecationWarning(
"PoseWithCovarianceStamped subscriber removed.")
55 Returns publisher for :setpoint_position: plugin, :local: topic 57 return rospy.Publisher(
mavros.get_topic(
'setpoint_position',
'local'), PoseStamped, **kvargs)
62 Returns publisher for :setpoint_velocity: plugin, :cmd_vel: topic 64 return rospy.Publisher(
mavros.get_topic(
'setpoint_velocity',
'cmd_vel'), TwistStamped, **kvargs)
def get_pub_accel_accel(kvargs)
def get_pub_attitude_cmd_vel(kvargs)
def get_pub_velocity_cmd_vel(kvargs)
def get_pub_attitude_throttle(kvargs)
def get_pub_attitude_posecov(kvargs)
def get_pub_position_local(kvargs)
def get_pub_attitude_pose(kvargs)