Running pixhawk from Odroid XU4

Hi,
Is there any clear instruction on how to control pixhawk from an odroid XU4.
I am building an AUV in which the image processing part will be done in Odroid XU4 and I want to use Pixhawk for controlling the thrusters as it gives better stability.

I have seen posts which shared raspberry pi image to make it a companion and then another PC is connected to the RPI to control the sub.

I am eager to know if there is any way to control the Pixhawk via USB from the Odroid using python script.
My AUV configuration is 2 motors for up/down and 4 motors(45 degrees) for movement.
It would be very helpful if I can get a blog or tutorial for the initial starting.

Thank you.

Hi Adnan,

I have seen posts which shared raspberry pi image to make it a companion and then another PC is connected to the RPI to control the sub.

We don’t have an Odroid XU4 image with companion installed and everything else configured.

I am eager to know if there is any way to control the Pixhawk via USB from the Odroid using python script.

I believe that is they way to go, you can connect the Pixhawk directly to your Odroid via USB and do the control/communicate with it via pymavlink, we have some examples here.

For your development, I would recommend to do a gstreamer pipeline to stream the video via udp to your surface computer and to the Odroid itself, with this you’ll be able to debug and see what is going on. Also it would be possible to test the UAV with your development code running in your surface computer.
The same thing applies to the mavlink communication, you can run a mavproxy server that can do the proxy communication with your surface computer and the pymavlink code in Odroid, with this you’ll be able also to do the development and debug from the surface computer.

Maverick has support for xu4.

Thank you Jacob,
Currently I am using the RPI as a companion PC and using UDP port to control from my PC using python script. I would definitely try the image with Odroid and let you know here.

Btw, Can you give me some hint
I want to keep the AUV in " Depth Hold" mode to keep it’s heading straight at a certain depth while accelerating forward.

I can change the mode to those and can also run motors but while AUV is headed perfectly forward.

This sounds fine, like normal operation.

I mean I want the AUV to move forward in Stabilized or Depth Hold mode. How can I do that ?

I attached the code I used below.

################################################################################
    import time
    from pymavlink import mavutil

############################################################## function to send RC values
def set_rc_channel_pwm(id, pwm=1500):
    """ Set RC channel pwm value
    Args:
        id (TYPE): Channel ID
        pwm (int, optional): Channel pwm value 1100-1900
    """
    if id < 1:
        print("Channel does not exist.")
        return

    # We only have 8 channels
    #http://mavlink.org/messages/common#RC_CHANNELS_OVERRIDE
    if id < 9:
        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.

# Create the connection
master = mavutil.mavlink_connection('udpin:192.168.2.1:3000')
# Wait a heartbeat before sending commands
master.wait_heartbeat()
# master.arducopter_disarm()
time.sleep(2)

############################################################## 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 = 'STABILIZE'

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


############################################################# Set some ptich
while True:
    set_rc_channel_pwm(1, 1700)
    time.sleep(.2)

When this mode stabilizes the ROV but does not go forward.

Rc channel 1 commands pitch. Redirecting...

1 Like

Thank you, it worked.
I put channel 1 at first, because I thought I need to map it according to the joystick in QGC.

1 Like