Regarding: pwm signal delays, setting target depth, type_masks and NED system, setting target attitude, heartbeat message

Hello Bluerobotics team,
I am trying to build an AUV for a competition.
There will be a yellow colored frame submerged in water. 1.5m width, 1.0m height, rectangle

I have trained a yolo deep learning model to recognize it but as someone who has no dedicated gpu I am getting ~11Fps out of my code which drops to 7fps when sending pwm signals and receiving attitude data. I have different components running on different threads which helps with the speed problem a little.
there are several vehicle components like attitude reading, sending pwm signal, displaying attitude and camera feed. How does one do all but in a fast manner?
My computer runs QGC almost flawlessly and i bet gqc is doing much more that what my Ui is doing yet it is still slower. What are some principle that qgc uses to do all this? paralel processing? multithreading? multiprocessing? async operations?
Also I am facing several problem which I hope you can help me with.

1.

My t-200 thrusters aren’t running smoothly. By this I mean they carry out the given command stutteringly (but in the correct direction). The aren’t getting the pwm signals fast enough I think.
So my first question is: What should the maximum delay between manual controls commands?
Ps. I am using Manual_control_send instead of rc override.

2.

I have set my vehicle to depth hold mode using the example code on the pymavlink gitbook.
The vehicle mode is correctly being changed to depth hold mode, which I can check both from the behavior the vehicle and from QGr.Con.
the problem I am having is with Setting a target depth.
I do have a bar30 pressure sensor installed.
I am again using the example depth target setting function from gitbook but I receive and error.
It says that the function mav.set.position_target_global_int_send got and argument of unexpected type: long_int
as far as I know python3.x does not have long_ints but I may be incorrect.

What could I do about this unexpected type error.
i tried writing -1.0 as simply -1, i tried non integer values like -0,5, -0,7 as well and the same error came up.
I used the code on ardusub site exactly.
(I got this error with 2 linux laptops and an imac so it seems that the issue is not influenced by operating system.)

def set_target_depth(depth):
    master.mav.set_position_target_global_int_send(
        int(1e3 * (time.time() - boot_time)), # ms since boot
        master.target_system, master.target_component,
        coordinate_frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
        type_mask=0xdfe,  # ignore everything except z position
        lat_int=0, long_int=0, alt=depth, # (x, y WGS84 frame pos - not used), z [m]
        vx=0, vy=0, vz=0, # velocities in NED frame [m/s] (not used)
        afx=0, afy=0, afz=0, yaw=0, yaw_rate=0
        # accelerations in NED frame [N], yaw, yaw_rate
        #  (all not supported yet, ignored in GCS Mavlink)
    )
set_target_depth(-1.0)

3.

Do the following functions need to be called in a while loop everytime or calling the functions once does the trick?

  1. changing flight mode
  2. setting target depth (if we dont want to change the value we already set)
  3. requesting message intervals
    4.sending manual control signals in stabilize mode (x,y,z,yaw,buttons)

4.

what does type_mask indicate in the above code. I can convert 0xdfe from hexadecimal to binary yet I dont know what it represents. Is there a chart of the possible other typemasks?

5.

Can I send a target attitude request to the auv even if I dont have any thruster that can do the command.?
For example my rov design has 6 thrusters and can’t do controlled movement in the pitch axis.
I often find that when I send a command like going forwards, the auv also moves in the pitch axis (probably because the back of the vehicle is lighter/heavier. )
If i send it a target attitude command request of (roll = 0, pitch=0, meaning it to be paralel to ground) would the function give me an error? will the vehicle try some kind of 2 axis rotation to get movement in the third axis? (rotating along x and y = rotate around z kind of way)

Is there some way to get the vehicle to be always paralel to the ground?

6

Regarding the heartbeat message:
I believe that when using QGC the heartbeat messages are sent by qgc to the vehicle. My question is:
Do we need to code a similar thing when we are coding with python(pymavlink)?
Does our code need to send heartbeat messages to the auv aswell or does pymavlink handle that in the background?/ heartbeat messages dont need to be sent when using pymavlink?

Hi ATP,

Just a few thoughts regarding your question 6:

  • The only reference I have found so far about sending heartbeat messages is this one: Python (mavgen) · MAVLink Developer Guide
  • Based on that, I tried implementing my own version of sending heartbeat messages to ArduSub using ROS but I couldn’t quite get it to work and I never figured out why. Maybe you can use this as a starting point.
from pymavlink import mavutil

class MAVLinkConnection(object):

    def __init__(self, device_address):
        self.connection = mavutil.mavlink_connection(device_address)
        self.connection.wait_heartbeat()

    def send_heartbeat(self, event=None):
        '''
        This function is called by an automated rospy.Timer from the main
        thread, which is why it needs the event parameter.
        '''
        self.connection.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,  # TYPE
                                           mavutil.mavlink.MAV_AUTOPILOT_INVALID,  # AUTOPILOT 
                                           0,  # BASE_MODE
                                           0,  # CUSTOM_MODE
                                           0)  # SYSTEM_STATUS

  • I also found that starting pymavlink as in the __init__ function above, or simply running the standard mavlink ROS node (roslaunch mavros apm.launch with the respective parameters), after starting QGC makes QGC lose its connection to the vehicle. There does not seem to be a problem when I start QGC after starting pymavlink since any other messages that I send through the pymavlink connection are received by the vehicle without any issues.

My conclusion for my own project was that I do not need to worry about sending heartbeat messages because the vehicle receives them from QGC, and that QGC needs to be started last.

Hope this helps.

This depends a lot on the code you’re using, the particular operations you need to do, and the hardware you’re running it on. It’s very difficult to comment in a meaningful way without access to that information, although I understand that since this is for a competition you may not be willing/able to share those details. As with every optimisation task, I’d suggest a good starting point is to profile your code, and see where the most time is being spent.

As a general principle for Python applications, I/O bound tasks should be handled asynchronously where possible (e.g. using coroutines (async) or threads), so that the other components of the program don’t need to be held up by waiting time. CPU bound tasks (where a lot of processing needs to occur) should be separated into their own processes where possible, but things get a bit more complicated if there needs to be a lot of communication between different processes, or if your computer has very few cores.

In this case your video stream receiving + processing steps could be done in one process, which then sends the detection info to a main process that can do something meaningful with it (perhaps through a pipe or queue). Depending on what you need to do with the telemetry and control signals it may be relevant to put that into its own process or it could be best to keep it as part of the main process.

QGC is a compiled application written in C++ - that means that most operations will be at least a bit faster, and it doesn’t have the same GIL threading constraints that Python does. It almost certainly uses some form of threading/multiprocessing, but I couldn’t tell you exactly where without looking at the source, which isn’t super easy to understand.

I believe this is determined by the pilot input failsafe, which defaults to 3 seconds.

Looks like there’s a typo for the longitude value in that example function - it should say lon_int=0 but currently says long_int=0. I’ve opened a pull request to fix that in our docs, but you should also be able to easily change that in your code :slight_smile:

1 and 2 are fine to set once, 3 should be fine to set once, although I have a vague memory there might have been an issue with that - I’ll ask the software team. For manual control see point 1.

As is specified in the docstring of that example function, it uses this mavlink message. The typemask is described there (in the mavlink docs).

You can send the request, but it won’t be able to achieve it. If you don’t have control over an axis then you don’t have control over it - if you try to gain control over it by rotating other axes until one of them aligns with the one you wanted to control then you’ve now lost control over one of the ones you previously had control over.

Is there some way to get the vehicle to be always paralel to the ground?

That’s quite subject to interpretation, but assuming you’re ok with minor fluctuations then sure, you just need enough control axes to do it, and a control algorithm that will provide that control for you. ArduSub will provide the algorithm if you provide the axes and the set point. If you need 6dof with only 6 thrusters then you could try a setup like this.

If minor fluctuations aren’t ok then I suppose it’s still possible, but only if you can remove/negate all external forces, which likely means you’d need to keep your vehicle on a solid surface (e.g. make it heavy and sink it to the bottom, or keep it on a table or the ground out of the water). From a stability standpoint you could also try making your vehicle large and flat, so that it strongly resists turning about the roll/pitch axes, but that also significantly increases drag for vertical motion.

Yes, heartbeat messages should be sent by whatever your control application is, be that QGC or your own pymavlink program.

No, pymavlink does not do this automatically in the background.

  • I’ve submitted a pull request to pymavlink for a background-thread-based approach here which hasn’t yet been accepted, and may not end up being. It does work however, so you’re welcome to use it if you want, but I’d suggest you read the discussion there to better understand when to use that over a synchronous/in-line approach. (Note that you’ll need to change the type parameter to GCS if you’re simulating a ground control station, as in @monsterbacke’s snippet)
  • For a synchronous approach you can instead use the periodic_event class from mavutil
  • It’s technically also possible to disable the heartbeat failsafe instead of sending a heartbeat, but it’s not recommended to do that because you could end up not being able to turn off your AUV even after losing contact with the control computer
1 Like

thanks a lot to both Anne and Eliot for your responses. It helped me a lot, though one thing is not sitting right with me:

When I checked the documentation for the meaning of the type_mask I saw that 1 corresponds to x, 2 → y, 4 -->z.
From what I understand turning these bits to 1 makes it so the vehicle ignores position target commands in the respective axes.

0xdfe corresponds to 0b110111111110. As I understand it, this means that the vehicle should ignore position target commands in all but the x axis. also it should not replace acceleration with force.
Shouldn’t the type_mask be 0b110111111011? or in terms of hexadecimal: 0xDFB?
(the bit corresponding with the z axis is 0 thus the vehicle doesn’t ignore commands in the z axis, which is what we want. )
Is there perhaps a difference in the implementation?

I had a look at the type mask and it seems like you’re correct, so I’ve added that fix to the pull request too :slight_smile:

Docs are now updated - thanks for finding those issues.

Following up on this, apparently mavproxy (which runs on the companion computer) automatically overrides requested streamrates every so often, so you’ll either need to send regular message interval requests or you can use the broad-brush approach of just setting the --streamrate parameter in the mavproxy options, which sets the rate for most (or possibly all?) the messages (in Hz, e.g. --streamrate=10 sets everything to 10Hz).

A post was merged into an existing topic: Vehicle isn’t executing target depth command correctly