forked from EEEManchester/mavros_mallard
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcmd2mav.py
39 lines (28 loc) · 1015 Bytes
/
cmd2mav.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Joy
from mavros_msgs.msg import OverrideRCIn
from geometry_msgs.msg import Twist
# Receives joystick messages (subscribed to Joy topic)
# axis 1 aka left stick vertical
# axis 0 aka left stick horizontal
def cmd2mav_callback(cmd_):
global pub
# Receives joystick messages (subscribed to Joy topic)
# axis 1 aka left stick vertical
# axis 0 aka left stick horizontal
# Joystick data input
cmd_vel = OverrideRCIn()
cmd_vel_y = 1500 + (400 * cmd_.linear.y)
cmd_vel_x = 1500 + (400 * cmd_.linear.x)
cmd_vel_r = 1500 + (400 * cmd_.linear.z)
cmd_vel.channels = [0, 0, 0, cmd_vel_r, cmd_vel_x, cmd_vel_y, 0, 0]
pub.publish(cmd_vel)
def cmd2mavros():
rospy.init_node('Cmd2mav')
global pub
pub = rospy.Publisher("/mavros/rc/override", OverrideRCIn, queue_size=10)
rospy.Subscriber("mallard_cmd_vel", Twist, cmd2mav_callback)
if __name__ == '__main__':
cmd2mavros()
rospy.spin()