SITL Ubuntu - Precision Landing with Companion Computer

Hi everyone,

I am trying to make the SITL of precision landing with companion computer feature work on Ubuntu. My setup is a Ubuntu installed in a Windows computer inside Virtual Box.

What I want to accomplish is very simple: Check that the Arducopter receive the landing target messages in Landing mode, from a Python script running Dronekit.

Below is my code for sending the message, a very simple one:

vehicle = connect(‘udp:0.0.0.0:14550’,wait_ready=True)

def send_land_message(x, y):
msg = vehicle.message_factory.landing_target_encode(
0, # time_boot_ms (not used)
0, # target num
0, # frame
(x-horizontal_resolution/2)*horizontal_fov/horizontal_resolution,
(y-vertical_resolution/2)*vertical_fov/vertical_resolution,
0, # altitude. Not supported.
0,0) # size of target in radians
vehicle.send_mavlink(msg)
vehicle.flush()

while(1):
if (vehicle.mode.name == “LAND”):
send_land_message(0,0)
time.sleep(0.1)
print “send”

My routine is:

  • Go to Arducopter folder and run “sim_vehicle.py --console --map”
  • arm throttle
  • takeoff 30
  • when it reach 30, switch to guided by “mode guided”
  • run the above Python script from another terminal
  • switch to land mode by “mode land”

I expect that the Arducopter can receive the landing target messages and control the vehicle accordingly however it just performs a normal landing. Looking on the flash log, the PL part (for precision landing) all components are zeros. At first I thought the way from Python to Arducopter was wrong, however, if I could send other messages just fine, for instance, this ned velocity message, the drone did move:

def send_ned_velocity(velocity_x, velocity_y, velocity_z):
msg = vehicle.message_factory.set_position_target_local_ned_encode(
0, # time_boot_ms (not used)
0, 0, # target system, target component
mavutil.mavlink.MAV_FRAME_LOCAL_NED, # frame
0b0000111111000111, # type_mask (only speeds enabled)
0, 0, 0, # x, y, z positions (not used)
velocity_x, velocity_y, -velocity_z, # x, y, z velocity in m/s
0, 0, 0, # x, y, z acceleration (not supported yet, ignored in GCS_Mavlink)
0, 0) # yaw, yaw_rate (not supported yet, ignored in GCS_Mavlink)
vehicle.send_mavlink(msg)
vehicle.flush()

Could anyone show me some guidance on this? My version is the latest 3.5 on Master. Can this be a bug?. Thanks!

Not knowing much about it here go some thoughts:

  • are your PLND_ENABLE and PLND_TYPE parameters correctly set?
  • are you using a rangefinder (even if it is a SITL simulated one)?
1 Like

Yeah I enabled the params PLND_ENABLE = 1 and PLND_TYPE = 1 (for companion not IR lock). Do we have to use a rangefinder to make it work? Do you know how to use them in SITL? Thanks!

1 Like

Thanks to Randy Mackay, I can make it work. My problem is not enabling the range finder in SITL.

RNGFND_TYPE 1
RNGFND_MIN_CM 0
RNGFND_MAX_CM 4000
RNGFND_PIN 0
RNGFND_SCALING 12.12

Might have to restart the SITL for the two last params (only show up when enabled). Thanks

Great you got it working! Sorry for not answering before. You do need a rangefinder for precision landing.

1 Like

hainh22
January 7

Thanks to Randy Mackay, I can make it work. My problem is not enabling the
range finder in SITL.

RNGFND_TYPE 1
RNGFND_MIN_CM 0
RNGFND_MAX_CM 4000
RNGFND_PIN 0
RNGFND_SCALING 12.12

Might have to restart the SITL for the two last params (only show up when
enabled). Thanks

Any chance of working up an example to go into dronekit-python?

I’ve been struggling with this for some days. I have a similar setup:

  • Running sim_vehicle.py -v ArduCopter -w --console using vagrant (ArduCopter v4.1)
  • Connected using pymavlink and sending a mock LANDING_TARGET msg (the velocity msg works perfectly)
  • Watching it on QGC waiting for it for move on any direction while it lands (doesn’t move)

I tried to set up a rangefinder like you do but I can’t pass the arming check (no rangefinder detected)

hertz = 40

drone = mavutil.mavlink_connection("udp:localhost:14550")
ht = drone.wait_heartbeat()
print(ht.to_json())

# RPi camera
horizontal_fov = math.radians(54)
vertical_fov = math.radians(41)
horizontal_res = 640
vertical_res = 480

# Also tried other values for x,y
while True:
    x = 600
    y = 400
    angle_x = (x - horizontal_res / 2) * horizontal_fov / horizontal_res
    angle_y = (y - vertical_res / 2) * vertical_fov / vertical_res
    drone.mav.landing_target_send(
        0,
        0,
        0,  # mavutil.mavlink.MAV_FRAME_BODY_NED # Tried this too
        angle_x,
        angle_y,
        0,
        0, 0  # Size of target in radians
        # horizontal_fov, vertical_fov # Tried these values too
    )

    time.sleep(1 / hertz)

What am I missing?

hello,

Check how we do it on autotest, it should help you : https://github.com/ArduPilot/ardupilot/blob/master/Tools/autotest/arducopter.py#L2784

Thank you for the reference.

I set those other params but it behaved the same, drone still fails to arm due to the rangefinder and testing without the check results in no movement when landing

I’ve been doing some tests lately and maybe this could help you.

At least in my case:

  • If you connect your script via udp, the messages never appear on the ground station (but the device does respond correctly on landing). If you connect it via serial port and use the -A argument, they do appear and you can check it in real time.

  • When using a serial device, I have not found a consistent way to set the connection baudrate. Sometimes it works, sometimes it won’t, and then it defaults to 9600 baud despite parameters or arguments. If using udp you don’t need baudrate.

  • The distance in your landing packet must be positive. If it’s zero or negative, the drone won’t move while landing. Also, if distance is always positive, it will keep landing endlessly, even underground.

Thank you for the advice.

Sadly, still no luck. Setting a positive distance has no effect. Im not sure how you mean to connect to SITL over serial.

btw, running autotest.py test.Copter.PrecisionLandingSITL pass without issues.

I’m talking about this: Using real serial devices