Hi,i want to control the thruster by python. I query some information,i know i should arm it and send RC. I connect one thrust to MAIN 1.I can test it by QGC,but when i run my code,the thruster doesn’t work.
This is my code.It can arm vehicle.What is problem?
import time
from pymavlink import mavutil
def set_rc_channel_pwm(channel_id, pwm=1500):
""" Set RC channel pwm value
Args:
channel_id (TYPE): Channel ID
pwm (int, optional): Channel pwm value 1100-1900
"""
if channel_id < 1 or channel_id > 18:
print("Channel does not exist.")
return
# Mavlink 2 supports up to 18 channels:
# https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE
rc_channel_values = [65535 for _ in range(18)]
rc_channel_values[channel_id - 1] = pwm
master.mav.rc_channels_override_send(
master.target_system, # target_system
master.target_component, # target_component
*rc_channel_values) # RC channel list, in microseconds.
# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
# Wait a heartbeat before sending commands
master.wait_heartbeat()
master.mav.command_long_send(
master.target_system,
master.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
0,
1, 0, 0, 0, 0, 0, 0)
# wait until arming confirmed (can manually check with master.motors_armed())
print("Waiting for the vehicle to arm")
master.motors_armed_wait()
print('Armed!')
set_rc_channel_pwm(1, 1700)
ArduSub uses a vehicle frame to determine which thrusters to activate when given a particular command - it can’t detect which or how many thrusters are connected. The rc_channels command operates on RC Inputs, so set_rc_channel_pwm(1, 1700) will specify a command of 1700 to the ‘pitch’ input. None of the default frames have any pitch component for thruster 1, so it’s not expected to activate with an input on channel 1.
If you want to control each thruster individually (at the cost of losing the ability to use ArduSub’s existing stabilisation modes and control algorithms) you could compile ArduSub with a custom frame configuration that’s set up with motion factors that make the first 6 input channels correspond to specific thrusters.
If you need fine-grained control of each thruster it likely makes more sense to implement that within ArduSub though (possibly as a custom flight mode), rather than as an external controller, because external control has more latency and less frequent sensor updates (e.g. IMU, compass, etc).
As a side note, I’ve pasted your text file contents into a code block, so people don’t need to download your file to view it. There are instructions for how make code blocks in the Formatting a Post/Comment section of the How to Use the Blue Robotics Forums post
I know the problem and change my code.
Then i connect two thrusters to MAIN 1 and MAIN 2 and use RC channel 4 to make vehicle yaw. But when i set the pwm as 1500,the thrusters work.I think they should not work. So here comes the problem,what is the mean of this pwm value? If i want to make vehicle yaw and set the left thruster’s pwm value 1600 ,the right 1400,what is the pwm value of code?
import time
from pymavlink import mavutil
def set_rc_channel_pwm(channel_id, pwm=1500):
""" Set RC channel pwm value
Args:
channel_id (TYPE): Channel ID
pwm (int, optional): Channel pwm value 1100-1900
"""
if channel_id < 1 or channel_id > 18:
print("Channel does not exist.")
return
# Mavlink 2 supports up to 18 channels:
# https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE
rc_channel_values = [65535 for _ in range(18)]
rc_channel_values[channel_id - 1] = pwm
master.mav.rc_channels_override_send(
master.target_system, # target_system
master.target_component, # target_component
*rc_channel_values) # RC channel list, in microseconds.
# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
# Wait a heartbeat before sending commands
master.wait_heartbeat()
master.mav.command_long_send(
master.target_system,
master.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
0,
1, 0, 0, 0, 0, 0, 0)
# wait until arming confirmed (can manually check with master.motors_armed())
print("Waiting for the vehicle to arm")
master.motors_armed_wait()
print('Armed!')
set_rc_channel_pwm(4, 1500)
time.sleep(1.5)
master.mav.command_long_send(
master.target_system,
master.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
0,
0, 0, 0, 0, 0, 0, 0)
# wait until disarming confirmed
master.motors_disarmed_wait()
print('disarmed!')
Well,i konw how to control thrusters.But i am confused about pwm value of YAW and FORWARD.
I test my pair of propellers with pwm generator one by one. I find that when the pwm
is 1590, No. 1 produces forward thrust,No. 2 produces backward thrust. It means that if i want ROV go forward,two thrusters should get different pwm value.
Here comes the problem ,when i set the code set_rc_channel_pwm(5, 1590),two thrusters produce backward thrust,what is the pwm value of No.1,Is it 1410? And due to the different characteristics of the forward and reverse rotation of the motor,when ROV go forward,it may yaw because of different thrust.Is my worry unnecessary?
Note that thrusters 1 and 2 in your diagram have their propellers in opposite directions (that’s what the colours represent). That means their optimal directions will be at opposite spins, so if they’re both pushing forwards they should have equal thrust.
If setting them individually to the same PWM yields opposite outputs, then yes one should be 1410 when both are pushing the same way and the other is set to 1590. You should be able to confirm that with the example script I linked you to (or just reading the SERVO_OUTPUT_RAW message yourself)
That shouldn’t be a problem if they’re both turning the correct direction to drive the vehicle the way you want. If they’re not turning the correct direction then you should check that you do actually have one clockwise and one counter-clockwise propeller, and that the thruster reverse/forward directions have been correctly set/determined (can be done in QGC).