-
-
Notifications
You must be signed in to change notification settings - Fork 44
/
set-servo.py
61 lines (52 loc) · 2.6 KB
/
set-servo.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
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
"""
Start the simulated vehicle as usual
Connect to it using MAVProxy with loading graph module like:
mavproxy.py --master=127.0.0.1:14550 --load-module="graph"
Make sure that SERVOx_FUNCTION is set to 0
Select a channel that is not used for flight operations
Observe the output with:
graph SERVO_OUTPUT_RAW.servox_raw
Where x is the selected channel
https://mavlink.io/en/messages/common.html#COMMAND_LONG
https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO
https://mavlink.io/en/messages/common.html#MAV_CMD_DO_REPEAT_SERVO
"""
import time
import pymavlink.mavutil as utility
import pymavlink.dialects.v20.all as dialect
# connect to vehicle
vehicle = utility.mavlink_connection(device="udpin:127.0.0.1:14560")
# wait for a heartbeat
vehicle.wait_heartbeat()
# inform user
print("Connected to system:", vehicle.target_system, ", component:", vehicle.target_component)
"""
# create set servo command
command = dialect.MAVLink_command_long_message(target_system=vehicle.target_system,
target_component=vehicle.target_component,
command=dialect.MAV_CMD_DO_SET_SERVO,
confirmation=0,
param1=6, # servo channel
param2=1900, # PWM value
param3=0,
param4=0,
param5=0,
param6=0,
param7=0)
# send the command to the vehicle
vehicle.mav.send(command)
"""
# create repeat servo command
command = dialect.MAVLink_command_long_message(target_system=vehicle.target_system,
target_component=vehicle.target_component,
command=dialect.MAV_CMD_DO_REPEAT_SERVO,
confirmation=0,
param1=6, # servo channel
param2=1900, # PWM value
param3=4, # count
param4=4, # period
param5=0,
param6=0,
param7=0)
# send the command to the vehicle
vehicle.mav.send(command)