dronekit / dronekit-python

DroneKit-Python library for communicating with Drones via MAVLink.
https://readthedocs.org/projects/dronekit-python/
Apache License 2.0
1.56k stars 1.44k forks source link

Indoor copter flight #697

Open IamBiswajitSahoo opened 7 years ago

IamBiswajitSahoo commented 7 years ago

I am working with dronekit python and using RPi 1 and Pixhawk with copter v3.3.3, in a gps denied environment.

Last few weeks I am trying to make the drone takeoff through python script but unable to do so as i dont know in a gps denied environment, what mode should i use to make the drone takeoff.

----------------next part i want to do-------------- And also I want to control the drone through an android mobile app having joystics on screen to send the exact values as of my transmitter and for that I am trying with RC Override but Im not able to takeoff or increase the throttle with rc override as it says cannot ARM:Throttle too high. ----------------next part i want to do--------------

But first of all, I want to takeoff the drone in GPS Denied environment, hover for few seconds and Land but I am not sure what mode to use instead of guided, with which simple_takeoff() will work.

NOTE: In STABILIZE the motors are disarming after some time instead of increase in their speed:

I am using the following code:

#/usr/bin/env python
# -*- coding: utf-8 -*-
from dronekit import connect,VehicleMode,LocationGlobalRelative
from pymavlink import mavutil
import time
# Receiving from command line
# import argparse
# parser = argparse.ArgumentParser()
# parser.add_argument('--connect',help="PORT_NO")
# args = parser.parse_args()

# Connecting to the vehicle
#connection_string = args.connect
connection_string = "/dev/ttyAMA0,57600"
print("Connecting to...% s" % connection_string)
vehicle = connect(connection_string, wait_ready=True)

#Function to arm and takeoff to a specified altitude
print(vehicle.mode)

# vehicle.mode = VehicleMode("LAND")
# time.sleep(5)
def arm_and_takeoff(aTargetAlt):
    print("Basic Prearm checks..dont touch!!")

    # while not vehicle.is_armable:
        # print("Waiting for vehicle to initialize")
        # time.sleep(2)

    print("Arming Motors..")
    # Copter should arm in Guided-mode
    vehicle.mode = VehicleMode("GUIDED")
    time.sleep(3)
    vehicle.armed = True

    while not vehicle.armed:
        print("Waiting for arming..:% s"% vehicle.mode)
        vehicle.armed = True
        time.sleep(2)

    print("Taking Off..")
    vehicle.simple_takeoff(aTargetAlt)
    time.sleep(5)

    while True:
        print("Altitude: ",vehicle.location.global_relative_frame.alt)
        #Break and return from function just below target altitude.
        if vehicle.location.global_relative_frame.alt>=aTargetAlt*0.95: 
            print("Reached Target Altitude..")
            modeLand()
            # print("Landing....")
            # vehicle.mode = VehicleMode("LAND");
            # print("Vehicle mode:%s"% vehicle.mode)
            break

def modeLand():
    print("Landing now")
    vehicle.mode = VehicleMode("LAND")
    time.sleep(5)
    print("-------------Vehicle is in:-------%s"% vehicle.mode)

arm_and_takeoff(2)
print(vehicle.mode)
print("Vehicle object closed")
vehicle.close()

And I have Optical flow Camera and a Lidar which i can use. Please help I'm stuck with this.

Regards Biswajit

IamBiswajitSahoo commented 7 years ago

No one here, who could help me with this??

hamishwillee commented 7 years ago

Gitter.

studroid commented 7 years ago

You can refer to this site: https://www.openmaker.co.kr/

And also I made a pull request: https://github.com/dronekit/dronekit-python/pull/712

Sorry for being late ;)

IamBiswajitSahoo commented 7 years ago

Thanks @studroid ,

I will look into it. And sorry for late response.

Regards Biswajit

ericksantillan commented 7 years ago

Ok, so I'm trying to fly a 3dr solo drone in a gps denied environment. When I tried to do: vehicle=connect('udpin:0.0.0.0:14550, wait_ready=True) There's this message that appears: >>> PreArm: Need 3D Fix so I downloaded this: http://qgroundcontrol.com/ I connected my drone via wifi (althought I think it's possible via USB) In the safetychecks I unchecked 'All' And then with a simple vehicle.armed=True the drone armed Hope it helps!

jacobfeldgoise commented 7 years ago

Try arming in "STABILIZE" mode instead of in "GUIDED" mode. This has worked well for me.

ncoop23 commented 6 years ago

Try this: Need a recent version of ArduPilot.

import sched, time, math
from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative
from pymavlink import mavutil # Needed for command message definitions

    flightalt = 20 #This is how high you want it to fly to
    vehicle = connect('0.0.0.0:14550')
    time.sleep(10)
    vehicle.channels.overrides = {}

    def arm_and_takeoffNoGPS(Target):

    #Arm the vehicle
        vehicle.mode    = VehicleMode("Guided_NoGPS")
    while not vehicle.is_armable: #Wait for the vehicle to be armable
        time.sleep(.5)

    vehicle.armed = True
    while not vehicle.armed:
        time.sleep(1)#Waiting for armed
    #Take Off
    thrust = 0.7
    while True:
        current_altitude = vehicle.location.global_relative_frame.alt
        if current_altitude >= Target*0.95:
            break
        elif current_altitude >= Target*0.6:
            thrust = 0.6
        set_attitude(thrust = thrust)
        time.sleep(0.2)

    def set_attitude(roll_angle = 0.0, pitch_angle = 0.0, yaw_rate = 0.0, thrust = 0.5, duration = 0):

    #Duration is seconds to do this for

    msg = vehicle.message_factory.set_attitude_target_encode(
        0,
        0,                                         #target system
        0,                                         #target component
        0b00000000,                                #type mask: bit 1 is LSB
        to_quaternion(roll_angle, pitch_angle),    #q
        0,                                         #body roll rate in radian
        0,                                         #body pitch rate in radian
        math.radians(yaw_rate),                    #body yaw rate in radian
        thrust)                                    #thrust

    vehicle.send_mavlink(msg)

    if duration != 0:
            # Divide the duration into the frational and integer parts
            modf = math.modf(duration)

            # Sleep for the fractional part
            time.sleep(modf[0])

            # Send command to vehicle on 1 Hz cycle
            for x in range(0,int(modf[1])):
                time.sleep(1)
                vehicle.send_mavlink(msg)

    def to_quaternion(roll = 0.0, pitch = 0.0, yaw = 0.0):
        """
        Convert degrees to quaternions
        """
        t0 = math.cos(math.radians(yaw * 0.5))
        t1 = math.sin(math.radians(yaw * 0.5))
        t2 = math.cos(math.radians(roll * 0.5))
        t3 = math.sin(math.radians(roll * 0.5))
        t4 = math.cos(math.radians(pitch * 0.5))
        t5 = math.sin(math.radians(pitch * 0.5))

        w = t0 * t2 * t4 + t1 * t3 * t5
        x = t0 * t3 * t4 - t1 * t2 * t5
        y = t0 * t2 * t5 + t1 * t3 * t4
        z = t1 * t2 * t4 - t0 * t3 * t5

        return [w, x, y, z]

    arm_and_takeoffNoGPS(flightalt)
ghost commented 6 years ago

@ncoop23 this did not work with dronekit sitl..where can we find copter 3.4?

ncoop23 commented 6 years ago

You need to green cube your solo then upgrade to 3.5. Look up proficnc they make the green cubes.

ncoop23 commented 6 years ago

Solex app for Android makes it easy to update your stuff. It isn't free so you need to decide how much your time is worth.

ghost commented 6 years ago

@ncoop23 i am trying on raspberry pi and pixhwak

prithvirajkumar97 commented 5 years ago

Hi .. I'm trying to perform a similar indoor navigation (using raspberry pi n pixhwak ) and facing a problem with the same code, where the drone is not responding towards the takeoff function ... But I'm able to arm and disarm from my python script. Can u assist me in solving the problem.Thanks in advance ...

ncoop23 commented 5 years ago

@prithvirajkumar97 You need to be in a mode that doesn't require GPS to pass arm checks. You can either disable the GPS in the arm checks which may end badly if it is actually trying to use it or use a mode that does not require GPS such as stabilize Link

prithvirajkumar97 commented 5 years ago

@ncoop23 I used the same code that was mentioned initially using vehicle.simple_takeoff(aTargetAlt) command... By skipping the pre-arm checks I'm able to arm my drone but the simple_takeoff() function doesn't seem to have any effect over the drone... The motors seems to get disarmed within the auto disarm timestamp after setting arm parameters and the throttle value also seems to be not increasing in response to TAKEOFF command....When I tried with Telemetry and QGroundControll, I got the status stating "TAKEOFF COMMAND FAILED ".... Since I'm trying to control the drone within a room I've removed the external GPS module ..... screenshot 79

jmachuca77 commented 5 years ago

The Copter needs to be in guided mode for that to work. Check to see if the mode is guided, or if the mode change failed for some reason and check the messages for the reason.

7, 2019, at 8:11 AM, prithvirajkumar97 notifications@github.com wrote:

@ncoop23 I used the same code that was mentioned initially using vehicle.simple_takeoff(aTargetAlt) command... By skipping the pre-arm checks I'm able to arm my drone but the simple_takeoff() function doesn't seem to have any effect over the drone... The motors seems to get disarmed within the auto disarm timestamp after setting arm parameters and the throttle value also seems to be not increasing in response to TAKEOFF command....When I tried with Telemetry and QGroundControll, I got the status stating "TAKEOFF COMMAND FAILED ".... Since I'm trying to control the drone within a room I've removed the external GPS module .....

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub, or mute the thread.

prithvirajkumar97 commented 5 years ago

@jmachuca77 Yaa the script successfully sets vehicle in guided mode .... I got the message ( "MODE CHANGE FAILED" ) only when I tried to takeoff in stabilize mode using telemetry ... Does the default pip install dronekit allows us to use GUIDED_NOGPS .... coz in one form they asked us to manually add keyword "GUIDED_NOGPS" mode in the list under pymavlink,is that enough inorder to use that mode in case?

prithvirajkumar97 commented 5 years ago

@Biswajit1995 @jmachuca77 @ncoop23 @studroid is there any way to control the throttle value, like to gradually increase it. Thanks in advance.

borhanreo commented 5 years ago

I am using a maxbotix sensor for indoor fly. sensor reading very good but copter did not stay my desired altitude.

`def arm_and_takeoff_nogps(aTargetAltitude):
DEFAULT_TAKEOFF_THRUST = 0.6
SMOOTH_TAKEOFF_THRUST = 0.5
# print("Basic pre-arm checks")
# while not vehicle.is_armable:
#     print(" Waiting for vehicle to initialise...")
#     time.sleep(1)
print("Arming motors")
vehicle.mode = VehicleMode("GUIDED_NOGPS")
vehicle.armed = True

while not vehicle.armed:
    print(" Waiting for arming...")
    vehicle.armed = True
    time.sleep(1)
print("Taking off!")
global thrust
thrust = DEFAULT_TAKEOFF_THRUST
while True:
    #current_altitude = vehicle.location.global_relative_frame.alt
    #if sonar_alt<4.00:
    current_altitude = sonar_alt
    print(" Altitude: %f  Desired: %f" % (current_altitude, aTargetAltitude))
    if current_altitude >= aTargetAltitude * 0.95:
        print("Reached target altitude Borhan ")
        thrust = SMOOTH_TAKEOFF_THRUST
        break
    elif current_altitude >= aTargetAltitude * 0.6:
        thrust = SMOOTH_TAKEOFF_THRUST
    set_attitude(thrust=thrust)
    time.sleep(0.2)`
gauravshukla914 commented 4 years ago

hi @Biswajit1995 I'm in a similar situation. I'm trying to use dronekit to fly my drone indoor in a gps denied environment. What would you suggest me to do?