Git Product home page Git Product logo

dronekit-python's Introduction

DroneKit Python

dronekit_python_logo

PyPi published version Windows Build status OS X Build Status Linux Build Status

DroneKit-Python helps you create powerful apps for UAVs.

⚠️ ATTENTION: MAINTAINERS NEEDED ⚠️

Hey it's true this project is not very active, but it could be with your help. We are looking for maintainers interested in keeping the project alive by keep up with CI and PRs. If you are interested in helping please apply by creating an issue and listing the reasons why you would like to help, in return we will be granting committer access to folks who are truly interested in helping.

Overview

DroneKit-Python (formerly DroneAPI-Python) contains the python language implementation of DroneKit.

The API allows developers to create Python apps that communicate with vehicles over MAVLink. It provides programmatic access to a connected vehicle's telemetry, state and parameter information, and enables both mission management and direct control over vehicle movement and operations.

The API is primarily intended for use in onboard companion computers (to support advanced use cases including computer vision, path planning, 3D modelling etc). It can also be used for ground station apps, communicating with vehicles over a higher latency RF-link.

Getting Started

The Quick Start guide explains how to set up DroneKit on each of the supported platforms (Linux, Mac OSX, Windows) and how to write a script to connect to a vehicle (real or simulated).

A basic script looks like this:

from dronekit import connect

# Connect to UDP endpoint.
vehicle = connect('127.0.0.1:14550', wait_ready=True)
# Use returned Vehicle object to query device state - e.g. to get the mode:
print("Mode: %s" % vehicle.mode.name)

Once you've got DroneKit set up, the guide explains how to perform operations like taking off and flying the vehicle. You can also try out most of the tasks by running the examples.

Resources

The project documentation is available at https://readthedocs.org/projects/dronekit-python/. This includes guide, example and API Reference material.

The example source code is hosted here on Github as sub-folders of /dronekit-python/examples.

The DroneKit Forums are the best place to ask for technical support on how to use the library. You can also check out our Gitter channel though we prefer posts on the forums where possible.

Users and contributors wanted!

We'd love your feedback and suggestions about this API and are eager to evolve it to meet your needs, please feel free to create an issue to report bugs or feature requests.

If you've created some awesome software that uses this project, let us know on the forums here!

If you want to contribute, see our Contributing guidelines, we welcome all types of contributions but mostly contributions that would help us shrink our issues list.

Licence

DroneKit-Python is made available under the permissive open source Apache 2.0 License.


Copyright 2015 3D Robotics, Inc.

dronekit-python's People

Contributors

afsafzal avatar amilcarlucas avatar danielhabib avatar fnoop avatar geeksville avatar georgehines avatar gwen-le-mero avatar hamishwillee avatar hefnysco avatar huibean avatar jmachuca77 avatar krufab avatar larsks avatar maruina avatar mgrennan avatar michael-hart avatar mohamedalirashad avatar mrpollo avatar o-gent avatar peterbarker avatar phmagic avatar pietrodn avatar roman-dvorak avatar sanderux avatar squilter avatar stephendade avatar tcr3dr avatar tribbloid avatar wsilva32 avatar yuuyafujiwara avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

dronekit-python's Issues

Autogenerated API ref missing some public API

localConnect and webConnect do not appear in the public API reference. I think they should - because they are what you use to get a hold of the APIConnection, and from this everything else.

@mrpollo Can you tell me what should / shouldn't be documented from this file - ie what is "private"?

API modifications to fix missing/confusing reference

The current API Reference is built from droneapi.lib module by Sphinx, which pulls it from comments in /droneapi/module/api.py and droneapi/lib/init.py. I've done a bit of a comparison of what is in the files and what is documented and have some suggestions:

DONE

  1. Documentation in init refers to objects as "base class" and has comments like "implemented in subclass". This is useful for a developer, but confusing for a user. If the base class is an interface, then it should just say what the interface does.

    HW I have updated these cases in the source so they are marked as "Internal notes"

  2. Attributes of Vehicle are documented in a table in the interface class. It would be better if these were part of the public "imported" API.

    HW I have updated these cases in the source using py:attribute markup. However it would be better if these were "properly" in the public API.

Split out

  1. CommandSequence.takeoff is missing in public API/documentation - created separate defect #70
  2. CommandSequence.next setter is not appearing in public API - #83 83
  3. Order source by preferred order of display to improve readability #84

good ideas from buzz

1 - the "check_home()" code that just confirms "home has been initialised", and
2 - the fact that in randy's code there is 4 different places where he has to "download the vehicle waypoints if we don't have them already" , presumably, "just to be sure"...?
3 - the send_nav_velocity() and condition_yaw() functions which would be convenient helper function/s in the drone.api directly. ... and probably the advance_current_cmd() function too... none of them are specific to the balloon thing in any way, and are clearly good-looking helper-apps to simplify the api or wrapper-up some common messages into something more human. :-)
4 - the move_to_balloon() , which should really be called move_to_position(), as that's what it does ( it contrains speed, and determines vector/s, and then calls send_nav_velocity() for the mavlink itself....

none of this is "balloon" code, it's really just convenience wrappers around the api....

Thoughts?
[5:49:46 PM] Kevin Hester: @buzz - I totally agree about 1, 3 & 4 (and will copy-paste this into a github so I don't forget)
[5:50:20 PM] Kevin Hester: 2 is probably just due to this being a 'rough'

DOC: Re-write the getting started section

The getting started section of the docs has a number of problems:

  • There is some duplication of commands for installing droneapi (ie done as a dependency and at the end)
  • The instructions to install Mavproxy aren't really needed as this is done automatically as it is a Droneapi dependency in pip
  • The instructions stop after installation. A get started should really go through to running an example.

Add Erle-Brain to the supported companion computers list

Propose add http://planner.ardupilot.com/wiki/other-project-and-common-topics/common-autopilots/common-erle-brain-linux-autopilot/ to http://python.dronekit.io/getting_started.html#supported-companion-computers under "Beaglebone Black" section.

This is an all-in-one package autopilot and companion computer - and as you will note has instructions and back links to our docs. I think it is quite important in that it is an "out of the box" solution for experimentation. I think I want one :-)

Agreed?

Provide information and vagrant file on how to contribute to docs?

We should make it easier for people to get started with contributing to the documents. The good news is that sphinx_3dr_theme can now be updated from pip, so it is now possible to set up sphinx and build the source without having to modify any files (previously you needed to modify the conf file in order to replace the theme).

I've written a vagrant script that does this. The proposal is to put this in /docs/ alongside the .rst files. The (windows) workflow would be:

  1. Create a fork of this project
  2. Clone the fork locally
  3. Navigate to your docs folder and run "vagrant up". This will bring up the VM, add sphinx and the theme, pull the latest code git, then build (call "make html").
  4. Users can then modify the files in their windows file system/notepadd++ and cause a new build by running: vagrant ssh -c "cd /vagrant && make html"
  5. They can commit the changes and do other git activities through windows. (or through the VM).

Is this approach desirable? Is the location of the vagrantfile in docs OK? (I think it is, but just checking).

In addition, I propose to update README.md to add information about how to contribute (specifically to the docs, but more generally it would be useful to cover how people can join the project?).

I would do this by adding a new heading "Contributing" near the end with a link "Contributing to the Documentation". That doc would explain how to use the vagrant file etc.

OK?

Support for Rally Points?

Is there a mechanism to support Rally Points?

These are not MAV_CMDs, and so it might be that there is no proper support for them through Command and CommandSequence.

They are created using MAVLINK_MSG_ID_RALLY_POINT

DOC: Gather introductory docs into own section

Currently we don't have a central place for non-technical material that explains what the project is about and how it can be used, and how developers can engage with it more closely (contribute) - though some of this material is spread throughout the sidebar.

The requirement is to group all the introductory material about what the API offers, contributing, licencing, supported companion computers, FAQ etc into one section.

implement set_mavlink_callback

from drone-platform:

Lastly, I was just wondering if you were going to implement the "set_mavlink_callback" method? I am not sure exactly why but my boss says that is something that he is looking for. I wish I had more information for you but all I know is that he says it is necessary for the project.

Yes, oops - I hadn't noticed that we had missed that one. Yes - I'll add that tomorrow and push out a new release. Also it is worth noting that all of the attributes on vehicle, waypoints, parameters etc... support callbacks which might be a better way to go. (see documentation for add_attribute_observer). What mavlink packets were you needing to watch for? I just want to make sure we didn't miss anything that really should be in the common (web enabled) interface instead.

Thanks for you time and all of the amazing effort you have put in on this project!

Implementation missing for battery_0_soc and battery_0_volt

There is no implementation for battery_0_soc and battery_0_volt. Please provide implementation and information about what parameters these map to on ardupilot (basically I need to know their "meaning" and possible values and units - so for example "Remaining capacity of the first battery in X units"

It is possible for a UAV to have multiple batteries, and two are specified in the parameters. This implies that there should actually be multiple values for these, or a way to index them.

I verified the lack of these parameters by inspection and testing. To test, I added the following lines to small_demo.py:

print "battery_0_soc: %s" % v.battery_0_soc
print "battery_0_volt: %s" % v.battery_0_volt

And got the exception:

Exception in APIThread-2: 'MPVehicle' object has no attribute 'battery_0_soc'
Traceback (most recent call last):
  File "C:\Users\hamis_000\Downloads\WinPython-64bit-2.7.6.4\python-2.7.6.amd64\lib\site-packages\droneapi\module\api.py", line 321, in run
    self.fn()
  File "C:\Users\hamis_000\Downloads\WinPython-64bit-2.7.6.4\python-2.7.6.amd64\lib\site-packages\droneapi\module\api.py", line 592, in <lambda>
    APIThread(self, lambda: execfile(args[1], g), args[1])
  File "small_demo.py", line 32, in <module>
    print "battery_0_soc: %s" % v.battery_0_soc
AttributeError: 'MPVehicle' object has no attribute 'battery_0_soc'

ROI helpers

It'd be nice to have ROI helpers, rather than using mavlink commands to set them.

Move channel_override examples out of simple_goto and small_demo

According to @tridge overriding channels is intended for simulating user input (ie in autotest) or for implementing joystick behaviour. It should not be used to directly drive a vehicle, except as a last resort. Instead the appropriate mavlink commands should be used.

The following examples set the channel_override in a way that we would not recommend:

I propose that we:

  • strip this from small_demo and simple_goto, and create a small independent demo that shows just this behaviour.
  • add a warning in the new example's code and docs about this use case
  • replace the throttle setting in the simple_goto with a more appropriate command for setting the throttle.

Troubleshooting follow_me.py

Hi Kevin,

Our team was able to run the follow_me.py example without debugging errors in two different ways. The first way we ran it, was exactly as the follow_me.py was written, and the second way was hardcoding one GPS coordinate in the Location function. However, in both cases we received the proper debugging output but the motors did not move.

The first way we ran it, was exactly as the follow_me.py was written. Our GPS USB dongle was providing GPS coordinates every two seconds, those coordinates were displayed, and the output showed “Got MAVLink msg: MISSION_ACK... etc.

The second way we ran it was with all the gpsd functions commented out and by hard-coding one GPS coordinate in the Location function.

After educating ourselves on your API, we believe that we have narrowed down the problem to being the goto function does not end up forcing the drone to move the motors.

Do you have any thoughts on why this could be happening.

We speculate that the problem may be that the drone is going into Guided mode. We believe that this is your intent. However, from our understanding, the drone will only go to locations autonomously in AUTO mode and only after the waypoints are saved and an rc command starts the motors.

Again, we do not fully understand what is wrong and why the command itself seems to be received by the APM, but the motors are not moving.

Again, we are able to get small_demo.py to move the motors properly, so we know it is not a problem with our wiring or our connection between the APM and our Raspberry Pi.

Any help is appreciated,

Thanks!

Attribute observer callbacks pass in the name of the attribute, not the value

This seems unexpected to me.

eg, If I call:
vehicle.add_attribute_observer('mode', mode_callback)

mode_callback is called with 'mode' as a parameter. I would expect to be passed the value of vehicle.mode. I'm not sure why I would want the name of the attribute, as I already know the name.

Perhaps the intention is for a single callback to handle multiple attributes? That seems odd to me, and the API does not enforce such a construct.

DOC: Getting Started - content and structural issues

http://python.dronekit.io/getting_started.html

  1. The companion computer information is not sufficiently visible because it is right at the end of a long document. It is also discussed in the body of the doc before it is mentioned. The section could be moved to the top (before SITL) or it more likely we could start with an introductory sentence explaining that we cover both setting up in a simulated environment and on a companion computer, with a link down.

[Update: This fixed by https://github.com/diydrones/dronekit-python/commit/4054edf65abd2f2ae24d0e02f7890e07a54728ca]

  1. The Companion computer link is not very helpful for explaining what you do next. It refers to different hardware and to the DroneAPI rather than DroneKit. As a reader I don't think it will be clear that they are the same thing, and what you do next. I think we need to use DroneKit terminology to make that link clear. It would also help possibly to have this/these docs written so that it is obvious which bit of the task is "installing dronekit".
  2. SITL and Installing DroneKit section feels a bit complicated:
  • Set up a simulated vehicle | Dependencies - is just wrong. Should be renamed to "Setting up in a Virtual Machine" and should be after the following "Setting up on Linux" topic.
    • Ideally we should note that there are timing issues in a VM but that it is still great for basic app testing.
    • Link to the VAGRANT setup as it is much better - provided it can do the job (?)
    • No need to talk about VirtualBox or whatever here as a dependency, that gets covered in the linked docs.
  • Installing DroneKit looks a bit odd because the "optional" dependencies are at the same level as thinks like setting up MAVLink.

Also we talk about installing dronekit on windows and MAC, and I find this confusing because we have SITL running on the VM. We need to make it clear where dronekit runs and how it fits with SITL simulation/MAVLINK.

Consider 2 options: a) putting the "dependencies" under a common heading. OR b) have an end to end topic "Setting up DroneKit on Linux" and then have separate sections covering setting up on Windows/Mac. These can just say "it's the same, but instead you need to do X, Y, Z"

Flight Replay example uses incorrect API

The Flight Replay example sets waypoints using mavutil.mavlink.MAVLink_mission_item_message directly. As I understand the API the correct type for a command in this API is "Command" (which is not even imported)

    cmd = mavutil.mavlink.MAVLink_mission_item_message(0,
                                                     0,
                                                     0,
                                                     mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
                                                     mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
                                                     0, 0, 0, 0, 0, 0,
                                                     lat, lon, altitude)
    cmds.add(cmd)

To fix this I believe the change is trivial, because the Command is just a thin wrapper around MAVLink_mission_item_message


from droneapi.lib import VehicleMode, Command
...
    cmd = Command(0,
                                                     0,
                                                     0,
                                                     mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
                                                     mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
                                                     0, 0, 0, 0, 0, 0,
                                                     lat, lon, altitude)
    cmds.add(cmd)

Hide non-implemented APIs from documentation

The API contains a number of APIs that are not fully implemented, and may never be. We do not intend people to use them at the current time. They are however publically visible and currently documented.

  • class Mission
  • get_mission
  • ConnectionInfo
  • web_connect
  • AuthInfo

IN addition there are APIs that are internal in that we don't expect people to call them (please confirm)

  • notify_observers - internal IMO
  • vehicle.delete - I think this is meaningless for a "local" vehicle? If not, what would it mean?

@mrpollo , is that a good set of items to hide/remove?

Obviously it is best that these are either fully implemented and so are usuable or are removed from the public API. In the meantime I propose:

  • Hide in the documented API. We can do this by adding this flag to the rst automodule directive
   :exclude-members: Mission, get_mission, ConnectionInfo, web_connect, AuthInfo, notify_observers
  • Remove all other mention of them in the documentation
  • Include status warnings ("not supported") in the source so that people reading the source can see these are not public and are intentionally not documented.

Note: This does not apply to "deprecated" APIs. APIs that might have been used by developers in the past need to be tagged as deprecated.

Thoughts?

How to store a set of waypoints for AUTO mode

Hi,

Mavlink allows you to set a group of waypoints to be executed by AUTO mode by using the "set waypointfile.txt" command.

Have you created a function that emulates the "set" command so that waypoints can be saved to the drone? I looked extensively in your documentation and I have not found anything that resembles this command.

I did notice that in small_demo.py you have access to the waypoints that are already set using cmds[x] structure:

cmds = v.commands
cmds.download()
cmds.wait_valid()
print "Home WP: %s" % cmds[0]
print "Current dest: %s" % cmds.next

However, you cannot save to the cmds[x] structure, you have only given access to printing the contents (at least as far as my experimentation has shown me).

If there is not such a function in droneapi yet, would you please make one? I do not mind making the text file if you could make some sort of function that "sets" the text file as the waypoints. However, It would be even more nice if you had a way to just "set" waypoints into the AUTO mode list using some sort of structure.

Thanks,

Stephen

Failure for non interactive use

reported via email:

Is there a way to call DroneAPI without the interactive MavProxy ?

I have MavProxy running in the background and the droneapi.module loaded:

screen -d -m -s /bin/bash mavproxy.py --master=/dev/ttyAMA0 --baudrate 57600 --aircraft OCTO8 --out=127.0.0.1:12345 --cmd="module load droneapi.module.api;" > /tmp/rc.log 2>&1

If I execute small_demo.py outside of interactive MavProxy it fails on this line:
api = local_connect()

I assume that the function would find my local running copy but I guess that is a wrong assumption?

Of course it runs fine inside the interactive MavProxy but only after it completes loading ….. so I can’t use the “api start” as a parameter.
Thanks

Timeout error when setting a parameter

When I try to set a parameter (for example RC1_TRIM) in my python script I receive the following message after a 2 second delay:

timeout setting RC1_TRIM to 1500.000000

However, when I check the value in MAVProxy the value has been set correctly. I found that this message is generated by mavset() in mavparm.py in pymavlink, so perhaps it is a bug there. For now I have commented out these lines (24-35) in mavparm.py to avoid having to wait 2 seconds for each parameter set.

Console issues

I've just started working with this api and so far it seems straight forward but I've been having some weird issues that might not be api problems specifically but not sure where else to ask about them. I'm running Yosemite on a macbook pro as fyi.
The issue is, I will run my script via the USB cable directly ( ex. mavproxy.py --master=/dev/cu.usbmodem1 --cmd="api start spray.py") it works like it should but if I connect via the usb radio adapter (ex. mavproxy.py --master=/dev/cu.usbserial-DN00B8MP --cmd="api start spray.py") then the api hangs anytime I change modes (ex. from GUIDED to ALT_HOLD) and I just see a MAV> console input

Add CommandSequence.takeoff to the public API

This is defined in the implementation class (not the interface class) and does not appear in the documentation.

It needs to be made visible in the documentation, ideally by defining it in the interface.

Note: I split this out from #64 so I can assign ownership to @mrpollo .

test-upload.py is not a dronekit-python example

test-upload.py shows how to upload a file to a service with the Cloud (REST) API, using Python. IMO that makes it something that belongs in the cloud example code, NOT in the dronekit-python example code.

When you've created a place for the cloud docs and issues, I'll move this across (assuming you agree)

Command Line Arguments and Import issue

Is it possible to have command line arguments for calling a script using api start?
Example "api start SmartCamera.py land -c 0"
When run I get "usage: api load "

Also when I run my script(without arguments), my script has problems completing imports. However, my script is able to complete imports when I run it normally(not with droneapi). Note: even if the script did complete imports it would crash due to lack of arguments.

I don't think I'm fully understanding the usage.

If it is helpful my program can be seen at github.com/djnugent/SmartCamera

Thanks,
Daniel

DOC: First paragraph of Python entry point improvements

http://python.dronekit.io/ (index.rst)

The text in the first paragraph might be improved:

DroneKit-Python provides interfaces for creating applications that run on an onboard Linux computer communicating directly to the autopilot of 3DR-powered vehicles or applications that run on a personal computer communicating with vehicles over a wireless connection.

It does talk about the fact that the API can be used on Linux computer and on ground stations (good). The problems are that it:

  • uses term "onboard Linux computer" where we use "Companion Computer" elsewhere.
  • does not specify the ground station OS other than saying "personal computer"
  • doesn't cover the benefits of a companion computer (desirable)
  • specifies "autopilot on a 3DR-powered vehicle - and this is suppose to be general.
  • The different communication methods for ground station vs companion computer is interesting but not quite as important.

Attribute observers result in endless output, even when script exited

Remove the comment on this line in small_demo.py to re-enable the mode.

So the code has

def mode_callback(attribute):
    print "Mode changed: ", v.mode

v.add_attribute_observer('mode', mode_callback)

When executed, the code runs. After the thread exits the mavproxy command prompt prints out the mode forever as shown below. This is a bug of some sort right?

AUTO>
AUTO> module load droneapi.module.api
AUTO> api start small_demo.py
AUTO> Mode: VehicleMode:AUTO
Location: Location:lat=-35.3632603,lon=149.1652287,alt=0.0,is_relative=False
Attitude: Attitude:pitch=0.00512621784583,yaw=-0.0500796176493,roll=0.00491848401725
Velocity: [-0.08, 0.08, 0.0]
GPS: GPSInfo:fix=3,num_sat=10
Armed: False
groundspeed: 0.0
airspeed: 0.0
Requesting 95 waypoints t=Wed Apr 29 14:56:15 2015 now=Wed Apr 29 14:56:15 2015
Home WP: MISSION_ITEM {target_system : 255, target_component : 0, seq : 0, frame : 0, command : 16, current : 0, autocontinue : 1, param1 : 0.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, x : -35.3632621765, y : 149.165237427, z : 584.090026855}
Current dest: 1
Disarming...
Arming...
Overriding a RC channel
Current overrides are: {'1': 900, '4': 1000}
RC readback: {'1': 1500, '3': 1000, '2': 1500, '5': 1800, '4': 1500, '7': 1000, '6': 1000, '8': Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}
1800}
Cancelling override
APM: Arm: Mode not armable
APIThread-0 exiting...
Got MAVLink msg: COMMAND_ACK {command : 400, result : 4}
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
Mode changed X:  VehicleMode:AUTO
...

Command API does not sufficiently abstract MAVLink_mission_item_message

The Command object is, I believe, a thin wrapper around a mavutil.mavlink.MAVLink_mission_item_message. It allows you to create a command object like this:

cmd = Command(0,
      0,
      0,
      mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
     mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
      0, 0, 0, 0, 0, 0,
       lat, lon, altitude)
cmds.add(cmd)

The values of the parameters are the same as the mavutil.mavlink.MAVLink_mission_item_message and I believe this to be a bug.

The problem is that I don't believe that most of these can or should be set by the user. It may be that they are already correctly set by the system, but IMO they should also be hidden. If we can't hide them we need to clearly state what values can be set, and this is not documented anywhere!

Specifically

  • target_system
    • - each part of a mavlink system gets a "target system" id for routing. This includes every UAV, GSCs etc. The number given has a default but is configurable
    • 0 is used for broadcast - goes to all systems in the network. For companion computers we would use this.
    • The thing is though, in practise a user can only get a command from the API for a specific Vehicle. This means that the target system is already known, and the user should not have to set it.
  • target_component:
    • This is a subsytem id within a target MAVLink system. Typically it is just the pixhawk, and you might as well use 0 (broadcast value)
    • It is possible for this to be an individual component like the camera.
    • Arguably this is useful, but again, the vehicle will know what subsystems it has (if any) and which commands can possibly be relevant to those subsystems.
  • seq:
    • The sequence number. When missions are uploaded to the autopilot, any command out of sequence is rejected. Given the fact that these are added etc in order by the system, there is no reason for the number not to be assigned automatically on upload.
  • frame - this is useful, but I will have to document.
  • current: current - Not intended for use in missions (represents the "curent command" but since we upload set of missions and ardupilot decides which we're up to is meaningless)
  • autocontinue: Intended to mark the end of a mission in the end of mission. Not implemented.

So in summary, lets hide target_system, target_component, seq, current, autocontinue from the API.

Simple CherryPy Server

I can't seem to get a simple CherryPy Server working with DroneKit. The code below works fine when I execute it out of mavproxy using python drone.py but when I enter mavproxy and execute it using api start drone.py , none of the CherryPy debug messages appear and I just get "STABILIZE> APIThread-0 exiting..."

#drone.py

import cherrypy

class HelloWorld(object):
    @cherrypy.expose
    def index(self):
        return "Hello world!"

if __name__ == '__main__':
   cherrypy.quickstart(HelloWorld())

I'm trying this on a RaspberryPi2 and the 'drone delivery" demo which also uses CherryPy works on it.

Docs: 3DR Logo missing from navbar on IE/Firefox

Should the "3DR" logo be displayed on top left of navbar? I see it on Chrome, but not Firefox or IE (for chrome I tried on a fresh browser, so I think it is not a caching issue).

Chrome:
image

On Firefox and IE:

image

Adding Camera support for Companion Computers

USB camera and other cameras support for companion computers. Potentially allowing developer to access live stream over LTE from the drone. Roadmap to create "periscope" like app for drones.

Docs: Minor link and layout defects in DroneKit-Python docs

http://python.dronekit.io/

  • No hyphen in DroneKit-Python's
  • Heading underlines too short

http://python.dronekit.io/getting_started.html

  • Italic for button presses. Better to use bold.
  • Heading underlines too short
  • Make consistent "first sentence capitalisation" for headings.

http://python.dronekit.io/first_app.html

Tidy heading levels

http://python.dronekit.io/example_1.html

  • inline code and console commands should be code highlighted.
  • Heading underlines too short
  • Title inconsistent capitalisation: "Simple Go to" to "Simple Go To"

http://python.dronekit.io/example_2.html

  • The link to "cherrypy" is broken
  • Bulleted list in second paragraph is broken
  • "location_callback" method and other inline code should be code highlighted.
  • Too-short markup under headings (results in unnecessary build warnings - having underlining too long doesn't matter)

http://python.dronekit.io/example_3.html

  • Fix heading underline lengths
  • Fix broken links - e.g. flight_replay.py
  • Add styling to inline code

http://python.dronekit.io/example_4.html

  • Fix heading underline lengths
  • Highlight a file path in italic.
  • Link to other docs.

Rename "Python DroneKit Doc"

This title is meaningless, and could apply to any of our docs in the kit :-)

This would be much better as "DroneKit Python API Reference". OK?

AttributeError: 'MPStatus' object has no attribute 'target_system'

Received the "AttributeError: 'MPStatus' object has no attribute 'target_system'" error when attempting to send a mavlink msg.

In api.py:392, neither self.mpstate.status or self.mpstate.settings had the target_system or target_component attributes set.

Details of setup, error, and .mavinit.scr follow below.

Setup

SITL
$ sim_vehicle.sh --console --map --aircraft test --out=$IP_ADDRESS:$PORT

MAVProxy
$ mavproxy.py --master=$IP_ADDRESS:$PORT

Error

Exception in APIThread-0: 'MPStatus' object has no attribute 'target_system'
Traceback (most recent call last):
File "/usr/local/lib/python2.7/dist-packages/droneapi/module/api.py", line 322, in run
self.fn()
File "/usr/local/lib/python2.7/dist-packages/droneapi/module/api.py", line 599, in
APIThread(self, lambda: execfile(args[1], g), args[1])
File "/home/igor/test_app/main.py", line 13, in
online system 1
AUTO> Mode AUTO
mgr.Start(api)
File "/home/igor/test_app/manager.py", line 94, in Start
self.enableFoo()
File "/home/igor/test_app/manager.py", line 392, in enableFoo
self.vehicle.send_mavlink(msg)
File "/usr/local/lib/python2.7/dist-packages/droneapi/module/api.py", line 244, in send_mavlink
self.__module.fix_targets(message)
File "/usr/local/lib/python2.7/dist-packages/droneapi/module/api.py", line 392, in fix_targets
message.target_system = status.target_system
AttributeError: 'MPStatus' object has no attribute 'target_system'


Contents of my ~/.mavinit.scr

module load droneapi.module.api
module unload terrain
module unload log
module unload battery
module unload fence
module unload rally
module unload calibration
module unload relay
module unload misc
module unload rc
api start /home/igor/test_app/main.py


Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.