Question on Signal Sending with Time Intervals by Pymavlinks

Hello,

I have been trying to follow the manual on the Pymavlink · GitBook.

Here is my code:

from pymavlink import mavutil

# Create the connection
master = mavutil.mavlink_connection('udpin:192.168.2.1:14550')
# Wait a heartbeat before sending commands
master.wait_heartbeat()

######################################################## function to send RC values
def set_rc_channel_pwm(id, pwm=1500):
    if id < 1:
        print("Channel does not exist.")
        return
    if id < 9:
        print("Signal Sent.")
        rc_channel_values = [65535 for _ in range(8)]
        rc_channel_values[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.

############################################################## Arm
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)

############################################################set mode :
# Choose a mode
mode = 'ACRO'

# Check if mode is available
if mode not in master.mode_mapping():
    print('Unknown mode : {}'.format(mode))
    print('Try:', list(master.mode_mapping().keys()))
    exit(1)

# Get mode ID: return value should be 1 for acro mode
mode_id = master.mode_mapping()[mode]
master.mav.set_mode_send(
    master.target_system,
    mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
    mode_id)

My question is about the output.

If I try just a single output

set_rc_channel_pwm(3, 1600)

or do it continuously like:

while true:
** set_rc_channel_pwm(3, 1600)**

or do different command continuously like:

set_rc_channel_pwm(3, 1600)
set_rc_channel_pwm(5, 1600)

The ROV works find, thursters works as expected.

But it will not work if there is any time interval between signals, like:

set_rc_channel_pwm(3, 1600)
time.sleep(10)
set_rc_channel_pwm(5, 1600)
time.sleep(0.2)

or the same one

set_rc_channel_pwm(3, 1600)
time.sleep(10)
set_rc_channel_pwm(5, 1600)
time.sleep(0.2)

or if I send use keyboard to send the signal
for example
press ‘w’ for forward and press ‘a’ for left

It will just process the first command and then stop working.

I have to wait for a while for the ROV to work again.

I guess it might be some override problem, could you please help me with it.

Thanks in advance!

Hi,

Check the safety section of the documentation.

The autopilot employs a some failsafe mechanisms to keep you and your equipement safe, as well as to prevent your ROV from running away from you during experiments.

All system components that communicate via MAVLink are expected to send a HEARTBEAT message at a constant rate of at least 1 Hz. If the autopilot does not receive a heartbeat from your application after this interval, it will trigger a failsafe.

When the autopilot is being commanded to move via RC_CHANNELS_RAW or MANUAL_CONTROL messages, the messages must be sent at a constant rate like the HEARTBEAT message. Otherwise, the autopilot will execute a failsafe if it has not received an updated command after a timeout period.

3 Likes

This topic was automatically closed after 27 hours. New replies are no longer allowed.