Indoors Quadcopter with ArduCopter 3.7 and Loiter Mode

Hello.
I’m programming an under 250g quadcopter to fly indoors autonomously, but I’m probably doing something wrong. I’ve followed the tips from @dollop and @ppoirier in this post and other few tips available on the web, but I couldn’t get it working in LOITER mode. So, basically, my small quadcopter setup is composed of a Kakute F7 AIO flight controller, Benewake TFMini LiDAR, ThoneFlow optical flow, and Matek GPS+Compass module. The parameters file is attached. All sensors were tested and are working outdoors and indoors. In GUIDED_NOGPS mode, it can take off smoothly with 0.51 of thrust. When the target altitude is reached, the thurst is set to 0.5 to keep it hovering. This code is below:

def takeoffGuidedNoGPS(self):
    # check if drone is ready to takeoff
    vstate = self.vehicle.system_status.state
    if vstate != "STANDBY":
        print(">> ERROR arming motors: vehicle is not ready for arming!")
        return False

    # change flight mode to GUIDE_NOGPS
    self.vehicle.mode = VehicleMode("GUIDED_NOGPS")
    while self.vehicle.mode.name != "GUIDED_NOGPS":
        print("Changing flight mode...\n")
        time.sleep(1)

    # arms the vehicle
    self.vehicle.armed = True
    while not self.vehicle.armed:
        print("Trying to arm vehicle...\n")
        time.sleep(1)

    # takeoff up to 0.7m and hover
    thrust = 0.51
    while True:
        current_altitude = self.vehicle.rangefinder.distance
        print("Hovering at %f meters.\n" % current_altitude)
        if current_altitude >= 0.7:
            thrust = 0.5
            break
        else:
            thrust = 0.51
        time.sleep(0.2)
        self.setAttitude(thrust=thrust)

    # hovering altitude reached
    print("Stationary hovering at %f meters.\n" % current_altitude)
    return True

The video below shows how it behaves executing the code above.

Initially, it goes a bit above the desired altitude and after goes down to the target altitude and stays hovering, but sliding horizontally. I’d like to use LOITER mode to fix position using LiDAR and optical flow, but nothing works in LOITER mode. It starts the motors for ~5 seconds and disarms. Any help will be very welcome.

Thanks in advance and best regards!

maroquio.sub250quad.indoors.setup.param (19.5 KB)

1 Like

Your floor is like a mirror , I suggest you use a textured rug to make the system more reliable.

Right. I will try to do it, although it fix position well when flying in LOITER mannually controlling. But for sure a textured rug will be better, so, I will do it tomorrow morning. Btw, do you know why I can’t take off programmatically in LOITER mode, but only in GUIDED_NOGPS?