Giter VIP home page Giter VIP logo

tum_ardrone's Introduction

Package tum_ardrone

This package contains the implementation corresponding to the following publications:

You can find a video on youtube. This Package builds on the well known monocular SLAM framework PTAM presented by Klein & Murray in their paper at ISMAR07. Please study the original PTAM website and the corresponding paper for more information on this part of the software. Also, be aware of the license that comes with it.

The code works for both the AR.Drone 1.0 and 2.0, the default-parameters however are optimized for the AR.Drone 2.0 by now.

Installation

with catkin

cd catkin_ws/src
git clone https://github.com/tum-vision/tum_ardrone.git -b hydro-devel
cd ..
rosdep install tum_ardrone
catkin_make

Quick start

Launch the nodes

roslaunch tum_ardrone ardrone_driver.launch
roslaunch tum_ardrone tum_ardrone.launch

Check status

On the GUI, under Drone Communication Status, you should see:

  • Drone Navdata: XHz (X > 100)
  • Pose Estimates: 33Hz

Keyboard control

  • focus drone_gui window
  • press ESC to activate KB control
  • fly around with KB (see drone_gui for key assignments)

Joystick control

  • rosrun joy joy_node
  • press PS button on controller to activate it
  • fly around (see drone_gui for key assignments)

Autopilot

  • type command "autoInit 500 800" in top-left text-field
  • click Clear and Send (maybe click Reset first) => drone will takeoff & init PTAM, then hold position.
  • click on video to interactively set target (relative to current position); see drone_stateestimation => first fly up 1m and then down 1m to facilitate a good scale estimate, dont start e.g. by flying horizontally over uneven terrain (!).
  • always have a finger on ESC or on the joystick for emergency-keyboard control :)

Nodes

drone_stateestimation

Estimates the drone's position based on sent navdata, sent control commands and PTAM.

IMPORTANT: requires messages to be sent on both /ardrone/navdata (>100Hz) and /ardrone/image_raw (>10Hz), i.e. a connected drone with running ardrone_autonomy node, or a .bag replay of at least those two channels. ardrone_autonomy should be started with:

rosrun ardrone_autonomy ardrone_driver _navdata_demo:=0 _loop_rate:=500

#### Subscribed topics

  • /ardrone/navdata
  • /ardrone/image_raw
  • /cmd_vel
  • /tum_ardrone/com

Published topics

  • /ardrone/predictedPose
  • /tum_ardrone/com

Services

None

#### Parameters

  • ~publishFreq: frequency, at which the drone's estimated position is calculated & published. Default: 30Hz
  • ~calibFile: camera calibration file. If not set, the defaults are used (camcalib/ardroneX_default.txt).
  • UseControlGains: whether to use control gains for EKF prediction.
  • UsePTAM: whether to use PTAM pose estimates as EKF update
  • UseNavdata: whether to use Navdata information for EKF update

UsePTAM and UseNavdata are set to false, the EKF is never updated and acts as a pure simulator, prediciting the pose based on the control commands received (on /cmd_vel). Nice for experimenting.

  • PTAMMapLock: lock PTAM map (no more KF)

  • PTAMSyncLock: lock PTAM map sync (fix scale and pose offsets etc.)

  • PTAMMaxKF: maximum amount of KF PTAM takes.

  • PTAMMinKFDist: min. distance between two KF (in meters)

  • PTAMMinKFWiggleDist: min. distance between two KF (relative to mean scene depth).

  • PTAMMinKFTimeDiff: min time between two KF.

PTAM takes a new KF if (PTAMMinKFTimeDiff AND (PTAMMinKFDist OR PTAMMinKFWiggleDist)), and tracking is good etc.

  • RescaleFixOrigin: If the scale of the Map is reestimated, only one point in the mapping PTAM <-> World remains fixed. If RescaleFixOrigin == false, this is the current pos. of the drone (to avoid sudden, large "jumps"). this however makes the map "drift". If RescaleFixOrigin == true, by default this is the initialization point where the second KF has been taken (drone pos. may jump suddenly, but map remains fixed.). The fixpoint may be set by the command "lockScaleFP".

  • c1 ... c8: prediction model parameters of the EKF. see "Camera-Based Navigation of a Low-Cost Quadrocopter"

#### Required tf transforms

TODO

#### Provided tf transforms

TODO

Using it

To properly estimate PTAM's scale, it is best to fly up and down a little bit (e.g. 1m up and 1m down) immediately after initialization. There are two windows, one shows the video and PTAM's map points, the other one the map. To issue key commands, focus the respective window and hit a key. This generates a command on /tum_ardrone/com, which in turn is parsed and does something.

Video Window

Video window

Key /tum_adrone/com message Action
r "p reset" resets PTAM
u "p toggleUI" changes view
space "p space" takes first / second Keyframe for PTAM's initialization
k "p keyframe" forces PTAM to take a keyframe
l "toggleLog" starts / stops extensive logging of all kinds of values to a file
m "p toggleLockMap" locks map, equivalent to parameter PTAMMapLock
n "p toggleLockSync" locks sync, equivalent to parameter PTAMSyncLock

Clicking on the video window will generate waypoints, which are sent to drone_autopilot (if running):

  • left-click: fly (x,y,0)m relative to the current position. image-center is (0,0), borders are 2m respectively.
  • right-click: fly (0,0,y)m and rotate yaw by x degree. image-center is (0,0), borders are 2m and 90 degree respectively.
Map Window

Map window

Key /tum_adrone/com message Action
r "f reset" resets EKF and PTAM
u "m toggleUI" changes view
v "m resetView" resets viewpoint of viewer
l "toggleLog" starts / stops extensive logging of all kinds of values to a file
v "m clearTrail" clears green drone-trail

drone_autopilot

PID controller for the drone. Also includes basic way-point-following and automatic initialization. Requires drone_stateestimation to be running. The target is set via the /tum_ardrone/com topic.

#### Subscribed topics

  • /ardrone/predictedPose

Published topics

  • /cmd_vel
  • /ardrone/land
  • /ardrone/takeoff
  • /ardrone/reset

Services

None

#### Parameters

  • ~minPublishFreq: usually, a control command is sent for each pose estimate received from drone_stateestimation. However, if no pose estimate is received for more than minPublishFreq milliseconds, a HOVER command is sent, causing the drone to hover if for example drone_stateestimation is shut down suddenly. Default: 110.
  • Ki_X, Kd_X, Kp_X: PID controller parameters for roll/pitch, gaz (up/down) and yaw.
  • max_X: maximal respective control command sent (ever).
  • rise_fac: rise commands are larger than respective drop commands by this factor. This is due to the drone sometimes dropping unpredictably fast for large drop commands, however rising somethimes requires large rise commands. aggressiveness: multiplied to PI-component of all commands sent. Low values lead to the drone flying "slower".

#### Required tf transforms

TODO

#### Provided tf transforms

TODO

Using it

The behavior of the autopilot is set by sending commands on /tum_ardrone/com of the form "c COMMAND". A Queue of commands is kept, and as soon as one command is finished (for example a way point reached), the next command is popped. The queue can be cleared by sending "c clearCommands". Commands can be sent using the drone_gui node. Some example scripts can be found in /flightPlans/*.txt. Possible commands are:

  • autoInit [int moveTimeMS] [int waitTimeMS] [int riseTimeMs] [float initSpeed]

      takes control, starts drone, initializes PTAM. That is:
      - starts the drone & and waits riseTimeMs, the drone will rise to approx. 
        a height of 1m. 
      - initializes PTAM by taking the first KF, flying up (sending initSpeed as control command) for moveTimeMS, 
        waiting waitTimeMS and then taking the second KF. 
        This is done until success (flying up and down respectively).
      - good default values are "autoInit 500 800 4000 0.5" 
    
  • autoTakeover [int moveTimeMS] [int waitTimeMS] [int riseTimeMs] [float initSpeed]

      takes control, initializes PTAM. The same as autoInit ..., 
      but to be used when the drone is already flying (skipps the first step).
    
  • takeoff

      - takes control, starts drone.
      - does not reset map or initialize PTAM
    
  • setReference [doube x] [double y] [double z] [double yaw]

      sets reference point (used in goto X X X X).
    
  • setMaxControl [double cap = 1.0]

      maximal control sent is capped at [cap], causing the drone to fly slower.
    
  • setInitialReachDist [double dist = 0.2]

      drone has to come this close to a way point initially
    
  • setStayWithinDist [double dist = 0.5]

      drone has to stay this close to a way point for a certain amount of time.
    
  • setStayTime [double seconds = 2.0]

      time the drone has to stay within [stayWithinDist] for target to be reached.
    
  • clearCommands

      clears all targets, such that the next command is executed immediately.
    
  • goto [doube x] [double y] [double z] [double yaw]

      flies to position (x,y,z yaw), relative to current reference point.
      blocks until target is reached according to set parameters
    
  • moveBy [doube x] [double y] [double z] [double yaw]

    moves by (x,y,z,yaw), relative to the current target position blocks until target is reached according to set parameters

  • moveByRel [doube x] [double y] [double z] [double yaw]

    moves by (x,y,z,yaw), relative to the current estimated position of the drone blocks until target is reached according to set parameters

  • land

    initializes landing (use auto-land of drone)

  • lockScaleFP

    sets the one point that does not change when the scale is re-estimated to the current drone position. The scaleFP can only be set when PTAM is good, i.e. this is delayed until PTAM is initialized and good. Need to set useWorldFixpoint in dynammic_reconfigure.

drone_gui

This node offers a simple QT GUI to control the drone_autopilot node, the drone_stateestimation node and fly the drone manually via keyboard or joystick.

#### Subscribed topics

  • /cmd_vel
  • /tum_ardrone/com
  • /ardrone/takeoff
  • /ardrone/land
  • /ardrone/reset
  • /ardrone/predictedPose
  • /ardrone/navdata
  • /joy

Published topics

  • /cmd_vel
  • /tum_ardrone/com
  • /ardrone/takeoff
  • /ardrone/land
  • /ardrone/reset

Services

  • calls /ardrone/togglecam
  • calls /ardrone/flattrim

#### Parameters

None

#### Required tf transforms

None

#### Provided tf transforms

None

Using it

Drone GUI

Monitor Drone, Autopilot and Stateestimation Nodes (top-right part).

On the top-right, the current publish-frequency of important topics is displayed:

  • Drone Navdata: monitors /ardrone/navdata. Should be around 150 to 200Hz with a connected drone, and running (and correctly configured) ardrone_autonomy node.
  • Drone Control: monitors /cmd_vel. This is the frequency of how often control commands are published (and sent to the drone).
  • Pose Estimates: monitors /ardrone/predictedPose. These are the state predictions generated by the drone_stateestimation node. By default, this should be 30Hz.
  • Joy Input: monitors /joy. If you have a connected game-pad and running joy_node, this should be different from 0Hz.
  • Pings (RTT): current wireless LAN latency (RTT in ms) for 500B and 20kB packages. If these are too high, reduce Wlan clutter.
Manual or joystick control of the drone.

The current control source has to be set (i.e. joystick or KB). The autopilot is only allowed to send control commands, if this is set to autopilot.

  • Joystick control requires a connected joystick and running "rosrun joy joy_node". We use a PS3 sixaxis controller. to make the controller work, a small linux-hack is required (set controller rights).

    • left joystick is horizontal pos. control; right joystick is height and yaw control.
    • L1 to take off, release L1 to land.
    • R1 to toggle emergency state. => by moving any of the two joysticks, the Control Source is immediately sent to Joystick. can be used for safety (autopilot does wired stuff -> immediately take over, disabling the autopilot and enabeling manual control).
  • KB control requires the GUI window to have focus, but NOT the upper-left text field. => make the GUI the active window and press ESC to immediately enable KB control and set focus such that KB control works properly. can be used for safety (autopilot does wired stuff -> press ESC and immediately take over, disabling the autopilot and enabeling manual control).

    • q,a: fly up & down.
    • i,j,k,l: fly horizontally.
    • u,o: rotate yaw.
    • F1: toggle emergency
    • s: takeoff
    • d: land
  • Buttons Land, Takeoff, ToggleCam, Emergency (toggles emergency state).

Autopilot Control
  • write commands in top-left text field (or load eample from one of the files). You can simply add .txt files to flightplans/.
  • click Send to transmit commands to the autopilot's command queue (automatically sets Control Source to Autopilot).
  • click Clear to clear autopilot command queue and current target.
  • click Reset to reset Autopilot, PTAM and EKF.

Troubleshooting

  • if drone doesnt start:
    • battery empty? (drone does not start if battery < ~18%)
    • Drone in emergency state? (if so, the four led's are red. click Emergency to reset).
  • cannot control drone:
    • selected correct control source? maybe re-select.
  • drone flies unstable using the autopilot:
    • adjust / reduce control parameters using dynamic_reconfigure (see readme_autopilot).
  • drone broken: buy a new one.

Known Bugs & Issues

  • as the software was originally developed for the Ar.Drone 1.0, the pressure sensor and magnetometer are not used.
  • drone_stateestimation crashes occasionally when PTAM init fails (crash occurs in PTAM code). Happens in oarticular if there is no baseline in between the first two keyframes, hardly ever happens in praxis.

Tips and Tricks

Camera calibration

  • front, old drone: 0.672049, 0.899033, 0.502065, 0.513876, 0.271972
  • front, new drone: 0.771557, 1.368560, 0.552779, 0.444056, 1.156010

calibrate with ethzasl_ptam. to work with colored images, in src/CameraCalibrator.cc change:

  • add #include <cv_bridge/cv_bridge.h>
  • change function imageCallback(...) to
void CameraCalibrator::imageCallback(const sensor_msgs::ImageConstPtr & img)
{
	cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);

	if(mCurrentImage.size().x != img->width || mCurrentImage.size().y != img->height)
		mCurrentImage.resize(CVD::ImageRef(img->width, img->height));

	memcpy(mCurrentImage.data(),cv_ptr->image.data,img->width * img->height);

	mNewImage = true;
}

Parameters: c1 to c8

can be estimated easily by

  • recording a flight: rosbag record -O calibFlight.bag /ardrone/image_raw /ardrone/navdata /cmd_vel
  • playing back that flight: rosbag play -l calibFlight.bag
  • starting two stateestimation nodes, one with remapped name and output:
    • rosrun tum_ardrone drone_stateestimation __name:=drone_stateestimationn2 /ardrone/predictedPose:=/ardrone/predictedPose2
    • rosrun tum_ardrone drone_stateestimation
  • plotting the respective estimated values
    • e.g.: rxplot /ardrone/predictedPose/dx,/ardrone/predictedPose2/dx
  • using dynamic reconfigure to
    • in drone_stateestimation2, use only control gains
    • in drone_stateestimation, use NO control gains, but instead navdata / speeds / PTAM.
  • setting c_i in drone_stateestimation2 such that graphs match best (play around).

Parameters: PID control

approximate in "simulation" based on c1 to c8:

  • play back any record, to make stateestimation run (dont play /cmd_vel)
    • rosbag play -l calibFlightZ.bag --topics /ardrone/image_raw /ardrone/navdata
  • run stateestimation, in dynamic reconfigure set only control updates to be used
  • run gui and autopilot, and control
  • plot control / respective pose e.g. with
    • rxplot /ardrone/predictedPose/yaw /cmd_vel/angular/z

Licence

The major part of this software package - that is everything except PTAM - is licensed under the GNU General Public License Version 3 (GPLv3), see http://www.gnu.org/licenses/gpl.html. PTAM (comprised of all files in /src/stateestimation/PTAM) has it's own licence, see http://www.robots.ox.ac.uk/~gk/PTAM/download.html. This licence in particular prohibits commercial use of the software.

tum_ardrone's People

Contributors

jakobengel avatar lesire avatar mani-monaj avatar rohanbhargava11 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

tum_ardrone's Issues

Cooperative SLAM using tum_ardrone

Hi,
I am trying to do my Master's Thesis on Cooperative SLAM using tum_ardrone package. I have made this package work for a single quadrotor and now moving further, I want to do cooperative slam wherein two quadrotors can share the map information with each other. tum_ardrone shows the map while running drone_Stateestimation node but I am trying to figure out to share this map to other quadrotor.
Kindly give suggestions.

Subscribing filter_state

How to subscribe the topic tum_ardrone/filter_state in a program?

What are the dependencies, header files that are need to be added with my program?

Waiting for first navdata to determine drone version

Hi,

I downloaded and was able to compile this program on Ubuntu Linux 12.04 (under Parallels) in Mac OSX 10.9. I'm using ROS Hydro.

I'm able to use the keyboard to fly the ardrone - but I cannot get video for PTAM. The PTAM Video window does not even show. PTAM Drone Map View shows, and the console for state_estimation shows this all the time.
"Waiting for first navdata to determine drone version"

Under tum_ardroneGUI, I can see under Node Communication Status that the Drone Navdata is 0Hz.

Anyone knows how I can fix this? Is my ar drone 2.0 broken or something?

Thanks, appreciate if anyone could help!

[rosrun] Couldn't find executable named drone_gui

Hello! I'm from China and I have met a problem when I used tum_ardrone. I install the ROS hydro on Ubuntu 12.04 LTS. I successfully implemented the catkin_make command, but when I run command roslaunch tum_ardrone tum_ardrone.launch, there was an error:
ERROR: cannot launch node of type [tum_ardrone/drone_stateestimation]: can't locate node [drone_stateestimation] in package [tum_ardrone]
ERROR: cannot launch node of type [tum_ardrone/drone_autopilot]: can't locate node [drone_autopilot] in package [tum_ardrone]
ERROR: cannot launch node of type [tum_ardrone/drone_gui]: can't locate node [drone_gui] in package [tum_ardrone]

And I also used the command rosrun tum_ardrone drone_stateestimation (actually I type the drone_stateestimation by myself because it didn't auto complete when I press tab-key), and there was an error like:
[rosrun] Couldn't find executable named drone_gui below /home/lmin/Documents/ros/catkin_ws/src/tum_ardrone

I have searched the answer on google but it seemed that only few people had met this problem, so I decided to ask you! Thank you and sorry for my poor English.

PTAM map plotter

Hello,

What method have you used to map the path taken by the drone. Does it fuse data from the IMU and the camera or is simply integration of the accelerometer using a filter to find the position.

Update source

Hi
How connect with author ( @JakobEngel ?) for double check my mods and post it for all?
Mods little - errors with gcc 4.7 & groove...

Hovering Drift

Hi,

First, thank you for this package. I have been following some of the UAV work from TUM and I must say its pretty impressive.

I've been following this project for a while now, but it seems that everytime I get it running on my AR Drone the hovering simply doesn't work. My drone ends up wandering around the area its supposed to be hovering until it eventually crashes.

I have good features at about 3m from the drone. I've modified to Kalmann Filter parameters as best I could. I've been playing around with the aggressiveness and the PID parameters, but I still can't seem to get it to hover in place.

Is there anything I'm missing? Am I doing something wrong? Do you have any recommendations for the setup I should have (features, space, etc). Finally, would it be possible to get a slightly more detailed calibration procedure?

I know its a lot of questions, but I am hoping to use this for a research project to control several UAVs.

Thank you for your time!

Oscar

Rotation with more than 180 degrees

Hi, I am using this package for my research and I must say it has been extremely useful. I am hoping to develop some sort of autopilot for the ARDrone, but have run into an issue with rotating past 180 degrees. Has anyone encountered this?

It seems like the drone gets "stuck" (never reaches the current target) whenever it crosses that threshold. You can recreate this easily by starting up the drone and sending incremental commands like:

goto 0 0 0 10
goto 0 0 0 20
.
.
.
and so on until you reach 180. Going past this number becomes impossible and you have to clear the command queue before the drone can move past it.

The problem is easily fixable by changing the reference pose, but it seems like there is a bug somewhere. It's worth noting that this does not seem to be a problem with ardrone_autonomy as similar tests have no problem.

Reviving tum_ardrone

Message to all tum_ardrone user/dev, and specially addressed to @JakobEngel @dgitz @Lolu28 @Horizon0156 @phuicy @ffurrer @jennyhasahat

tum_ardrone looks dead when you look at the project activity (commits, pull requests, ...). However, I have just had a look at the forks, and a lot of people are forking and updating this code. Several of us have updated the package to use catkin. Some of us have made some quite specific updates: I personally tried to use actionlib in place of the script language, others implemented publication of PCL data, odometry, multiple drone version, ...

Maybe its time to converge and have a unique repo, with maybe several maintainers, and some branches on it so that the project may look alive again!

What is your opinion on that and your view of maintaining tum_ardrone?
Is there somebody from tum-vision here that may transfer or add maintenance to more active devs?

tum_ardrone with downward looking camera

Hi
Is it possible to use tum_ardrone for bottom looking drone camera.
Iv modified the parrot front looking camra to downward looking. Apart form sending the corrent /tf what else i need to modify?

Thanks

Error with rosdep

Hi,
I have this configuration:
ROS version: Indigo 1.11.9
OS version: Ubuntu 14.04 32 bits
gcc version 4.8.2 (Ubuntu 4.8.2-19ubuntu1)

I follow this instructions of https://github.com/tum-vision/tum_ardrone

cd catkin_ws/src
git clone https://github.com/tum-vision/tum_ardrone.git -b indigo-devel
cd ..
rosdep install tum_ardrone
mogu@lnums:~/catkin_ws$ rosdep install tum_ardrone

ERROR: Rosdep cannot find all required resources to answer your query
Missing resource tum_ardrone
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/home/mogu/rosbuild_ws/package_dir
ROS path [2]=/opt/ros/indigo/share
ROS path [3]=/opt/ros/indigo/stacks

can you help me ,any ideas?

tum_ardrone with downward camera

Hello,

I'm working with the ARDrone 2.0 and I would like to know whether it's possible to configure tum_ardrone package to use with downward camera (Actually I did some modification on the drone and now the forward camera is looking down)

Documentation feedback

Hi!
This is a great project, thank you for making this code freely available on the internet.

I've been writing a robot demonstration using the /tum_ardrone/com topic to send commands to drone_autopilot to make them swarm together at a target. I noticed a few things missing from the documentation along the way, and I thought I should let you know.

  • The command c start needs to be sent on the topic in order to turn the autopilot on. Without this, it won't start executing any of the /tum_ardrone/com commands.
  • Is there a way of resetting the PTAM through /tum_ardrone/com?
  • is there a command to make the drones hover nicely on the spot like in the demonstration video? http://youtu.be/eznMokFQmpc

One final thing, I forked the project and updated it for ROS Groovy, if you're interested? https://github.com/jennyhasahat/tum_ardrone

Couldn't find executable named error Ubuntu

I am trying to fly the ardrone parrot 2.0 using tum_ardrone ptam module. I ahd to make it first

       rosmake tum_ardrone

The above compiled with 0 failures. however, when I do the following commad

       rosrun tum_ardrone drone_stateestimation

I get the following error

      [rosrun] Couldn't find executable named drone_stateestimation below

      /home/bojan/fuerte_workspace/tum_ardrone

I tried to google and get a solid pipelined solution to check for the reason for this error and solve it, but I did not get it. Am new to ubuntu, thus your help is much appreicated. This error doesn't seem to be package specific since the same package works fine in another laptop I tested. Am runnign Ubuntu in vmWare. Does that make any difference? Or is it something am missing with the package.?

Thanks in advance

Problem with catkin installation

Hi when I run the command 'rosdep install tum_ardrone' I get the following error

ERROR: Rosdep cannot find all required resources to answer your query
Missing resource tum_ardrone
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/home/shehroze/rosbuild_ws/package_dir
ROS path [2]=/opt/ros/indigo/share
ROS path [3]=/opt/ros/indigo/stacks

I have tried adding "source /home/shehroze/catkin_ws_tumdrone/devel/bash.sh" to the .bashrc file but it didnt resolve the issue

Im currently using ubuntu 14.04 with ROS indigo

Cheers

Scale Calculation

In the file DroneKalmanFilter.h, the function computeEstimator that calculates the optimal value for the scale has sigma_PTAM squared in the denominator (Line 56 ). However in both your papers and the thesis, the formula has a sigma_PTAM inverse * sigma_IMU. If this is only a typo, it can have big errors in the actual scale calculation, yes?

Couldn't find any executable files.

HI,

I am trying to use the tum_ardrone for my ardrone.

I installed all of the packages such as Indigo, ardrone_autonomy, tum_ardrone.

I couldnot execute the drone_gui, drone_stateestimation, and so on.

I guess it is not about the environment problem since anyother example is working except tum_ardrone.

Actullay, rosmake was not working for the compile. Therefore, I used catkin_make_isolated in order to compile tum_ardrone.

It doesn't show any errors.

Do you have any idea? Can I directly compile your tum_ardrone?

Rosdep issue

Hello!
I have followed the steps to install the package, but when I try to install dependencies with rosdep install tum_ardrone-indigo-devel I get the following error:
ERROR: Rosdep cannot find all required resources to answer your query
Missing resource tum_ardrone-indigo-devel
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/home/fernando/ros/stacks
ROS path [2]=/home/fernando/catkin_ws/src
ROS path [3]=/opt/ros/indigo/share
ROS path [4]=/opt/ros/indigo/stacks

I am using indigo version of ROS and I have tried with indigo-devel and hydro-devel branches

why not draw the map points and corner?

hello, I'm using the tum_ardrone, but the map window didn't draw the map points, and the video window didn't draw the corner, too. But the pitures of the introdution of tum_ardrone in ros had drawn, and the code also has the function plotMapPoints. Did I configure something wrong?

bug in DroneKalmanFilter.cpp

When adding a new PTAM Observation or a fake Observation, you check for the received time stamp against the variable 'predictedUpToTotal', a variable that doesn't seem to be updated ever after its initial declaration. Did you mean to check it against 'predictdUpToTimestamp' ?

Continuous Mapping

Is there a way to do SLAM on one ar.drone? I want to be able to add new keypoints to the map and do proper SLAM with the sparse map. Right now I believe the initial scene keypoints are tracked and no new keypoints are added as the drone moves about the environment. I remember PTAM has an easy way of configuring this - by unlocking the initial map. Any help on this? I want to be able to icrementally build up a map of the environemnt around the drone. It seems to be not picking up good new keyframes and features.

Performance when using Tum_ardrone

Hi everyone

Is there any way in the code to disable "Ptam drone camera feed" window for higher perfs?
Or have you any advices for saving CPU when using tum_ardrone and tum_simulator?
Thanks.

Covariance matrix of predicted state

state vector is being published in topic "/ardrone/predictedPose" i.e position, velocity, angles but there are no variances or covariance being published. I want to know the predicted covariance state also. Can anybody tell where are they being calculated in the code ? and where are their final values ?

/usr/bin/ld: cannot find -lglut

I was trying to install tum_ardrone package on ROS indigo but during catkin_make i got the following error:
/usr/bin/ld: cannot find -lglut
Do you have any idea how to resolve this?

How can I get an error message of my AR Drone?

Hi,
I start to use an AR Drone with this tum_ardrone package.

When I use an iPhon app to fly my drone,
I can get an error message in red on the top part of the screen of my iPhone (for example, Ultrasound Emergency).

However, when I use this tum_ardrone package as follows, I can find the error message neither on the terminals nor on the tum_ardrone GUI.

roslaunch tum_ardrone ardrone_driver.launch
roslaunch tum_ardrone tum_ardrone.launch

Is there any way to get an error message of my drone with this package?

Rotation Matrix in DroneController.cpp

Hi,
I have some doubts about your source code.
In DroneController.cpp file, from 141 to 145 line,

    d_term[0] = cos(yawRad)*d_error[0] - sin(yawRad)*d_error[1];
    d_term[1] = - sin(yawRad)*d_error[0] - cos(yawRad)*d_error[1];

    p_term[0] = cos(yawRad)*new_err[0] - sin(yawRad)*new_err[1];
    p_term[1] = - sin(yawRad)*new_err[0] - cos(yawRad)*new_err[1];

It seems a little bit wired, why the rotation matrix is [cos, -sin; -sin, -cos] not [cos, -sin;-sin cos] as the general SO(2) ? Would it be possible to share some more information about this part?

Updating the goal

Hi there-- this is a great piece of work. I have only just started fiddling with it.

I think I'd like to be able to update the goal position before the drone actually reaches the goal. I've reviewed the code briefly and I think I know how I would do this, but before I dive in I'd appreciate your feedback.

I'm thinking I would add another command to the comCb callback with some sort of "updateGoal" command. The command then wouldn't go on the stack, but it would check to see if currentKI was non-NULL, and then call a new method on the KI, "updateGoal" which changes the goal. If the 'currentKI' was a KI without a goal (i.e., not a KIFlyTo), then updateGoal would return an error...

(There would be two updateGoal commands, one which took an absolute position and one that took a relative position, just like the fly to commands, but both would call the same updateGoal method.)

If would be nice to figure out a way where the user would not have to figure out if a KIFlyTo command were currently active though, and it could just send a command and the drone would either create a new KIFlyTo if there wasn't one already active. Maybe another approach would be to have a separate non-blocking command channel?

In order to actually change the goal in the controller could I just call setTarget or would I need to reset the PID controller as well? (my understanding of control systems is quite limited at this stage.)

Thanks
-s

SLAM auto-registration/Loop Closure

As the code is currently written I believe that loop closure is currently not possible. Additionally, if the drone performs a slam initialization in say the North direction and rotates to the South direction any pose information will not be correct. We are currently working on including this ability, by at least one of the following methods:
-During the SLAM registration process, the drone performs this several times while being oriented in several directions. When SLAM is running, the drone will pick the best keyframe points it sees and perform SLAM on that.
-Periodically (or when it no longer sees the keyframe points) the drone will restart the SLAM registration process while keeping the current point cloud and pose information.

It would be really helpful if the registration process was modified to allow rotation movements (instead of translation), as that will have much less impact on pose interference.

After the SLAM process is better automated we will start working on loop closure.

Error in stateestimation catkin_make

Hi,

I'm amazed by your ardrone projects and I bought a ardrone and compile codes (catkin) follow your instructions.

but during the compiling, I always get the following error:

/home/arlxps/catkin_ws/src/tum_ardrone/src/stateestimation/GLWindow2.cc: In member function ‘void GLWindow2::SetupWindowOrtho()’:
/home/arlxps/catkin_ws/src/tum_ardrone/src/stateestimation/GLWindow2.cc:106:17: error: cannot convert ‘CVD::ImageRef’ to ‘GLdouble {aka double}’ for argument ‘1’ to ‘void glOrtho(GLdouble, GLdouble, GLdouble, GLdouble, GLdouble, GLdouble)’
make[2]: *** [tum_ardrone/CMakeFiles/drone_stateestimation.dir/src/stateestimation/GLWindow2.cc.o] Error 1
make[2]: *** Waiting for unfinished jobs....
[ 91%] Built target trainMarkerBundle
make[1]: *** [tum_ardrone/CMakeFiles/drone_stateestimation.dir/all] Error 2
make: *** [all] Error 2

Can you please help me and give me some hints how to fix this error?

p/s: I have installd TooN, and reconfigure the libcvd too. But no luck too.

Your help is highly appreciated. Look forward for your reply.

Thank you in advanced.

regards,
jayden

dataset of PTAM

Thank you very much for your project.
Could you provide the dataset of PTAM?

Camera hangs and program crashes

When I run the program, the camera view hangs after a second. I get a warning about camera calibration file not found, and drone_stateestimation crashes quickly. Sometimes, my whole computer crashes. Any advice on how I can troubleshoot this? Maybe something is built incorrectly or something is wrong with my environment.

SUMMARY
========

PARAMETERS
 * /rosdistro: jade
 * /rosversion: 1.11.16

NODES
  /
    drone_autopilot (tum_ardrone/drone_autopilot)
    drone_gui (tum_ardrone/drone_gui)
    drone_stateestimation (tum_ardrone/drone_stateestimation)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[drone_stateestimation-1]: started with pid [3062]
process[drone_autopilot-2]: started with pid [3063]
process[drone_gui-3]: started with pid [3064]
Object::connect: No such slot tum_ardrone_gui::FlatTrimClicked()
Object::connect:  (sender name:   'buttonFlattrim')
Object::connect:  (receiver name: 'tum_ardrone_guiClass')
nouveau: kernel rejected pushbuf: Invalid argument
nouveau: ch0: krec 0 pushes 1 bufs 0 relocs 0
[drone_stateestimation-1] process has died [pid 3062, exit code -11, cmd /opt/ros/jade/tum_ardrone/bin/drone_stateestimation __name:=drone_stateestimation __log:=/home/ethan/.ros/log/4764c088-ad49-11e5-a956-20c9d042f419/drone_stateestimation-1.log].
log file: /home/ethan/.ros/log/4764c088-ad49-11e5-a956-20c9d042f419/drone_stateestimation-1*.log

The log file says:

�[0m[ INFO] [1451296663.823101385]: Started TUM ArDrone Stateestimation Node.�[0m
set publishFreq to 30Hz
set calibFile to DEFAULT
set ts base to 1451296663
Waiting for Video
Found ARDrone Version 2
Set Camera Paramerer to: 0.771557 1.36856 0.552779 0.444056 1.15601
�[0m[ INFO] [1451296664.216022236]: Video resolution: 640 x 360�[0m
new delasXYZ: 40, delayVideo: 70, delayControl: 90
new delasXYZ: 40, delayVideo: 69, delayControl: 87

minor bug in controller

Line 87, KIFlyTo.cpp,

if(!reached && diffDistSquared < initialReachedDist * initialReachedDist && diffYaw < 5)

shouldn't you check for the absolute value of diffYaw?

Error during rosmake tum_ardrone

Servus,

I'm new to ROS and am currently trying to set up this package.

I downloaded and installed ROS according to the tutorials, created a ros-workspace (not catkin) and followed your instructions.

But during the "rosmake tum_ardrone" i always get the following error:

make[3]: Betrete Verzeichnis '/home/fabi/ros_ws/tum_ardrone/thirdparty/libcvd/build'
g++ -O3 -I. -I. -INONE/include -g -Wall -Wextra -pipe -ggdb -fPIC -mmmx -msse -msse -msse2 -msse3 -pthread -c progs/video_play_source.cc -o progs/vi$
progs/video_play_source.cc: In Funktion »void play(std::string)«:
progs/video_play_source.cc:200:17: Fehler: es gibt keine Argumente für »usleep«, die von einem Templateparameter abhängen, weshalb eine Deklaration vo$
progs/video_play_source.cc:200:17: Anmerkung: (mit »-fpermissive« wird G++ den Code akzeptieren, aber die Verwendung eines nicht deklarierten Namens i$
progs/video_play_source.cc: In Instanziierung von »void play(std::string) [with C = CVD::Rgb; std::string = std::basic_string]«:
progs/video_play_source.cc:241:30: von hier erfordert
progs/video_play_source.cc:200:4: Fehler: »usleep« wurde in diesem Gültigkeitsbereich nicht definiert
In file included from ./cvd/internal/convert_pixel_types.h:27:0,
from ./cvd/image_convert.h:25,
from ./cvd/colourspacebuffer.h:27,
from ./cvd/videosource.h:13,
from progs/video_play_source.cc:38:
./cvd/internal/scalar_convert.h: Im globalen Gültigkeitsbereich:
./cvd/internal/scalar_convert.h:112:21: Warnung: »CVD::Pixel::Internal::init_float_for_byte« definiert, aber nicht verwendet [-Wunused-variable]
./cvd/internal/scalar_convert.h:113:21: Warnung: »CVD::Pixel::Internal::init_double_for_byte« definiert, aber nicht verwendet [-Wunused-variable]
make[3]: *** [progs/video_play_source.o] Fehler 1
make[3]: Verlasse Verzeichnis '/home/fabi/ros_ws/tum_ardrone/thirdparty/libcvd/build'
make[2]: *** [libcvd_built] Fehler 2
make[2]: Verlasse Verzeichnis '/home/fabi/ros_ws/tum_ardrone/thirdparty/libcvd'
make[1]: *** [all] Fehler 2
make[1]: Verlasse Verzeichnis '/home/fabi/ros_ws/tum_ardrone/thirdparty'
make: *** [all] Fehler 2

FFMPEG is installed, do I need anything else?

Kind regards,
Fabi

Flat Trim not Working from GUI (problem in "tum_ardrone_gui.ui" line 743

Flat Trim button does not actually result in the flat trim service being called. It looks like the section for connection "buttonFlatTrim" in "tum_ardrone_gui.ui" sets the slot to "FlatTrimClicked()" (line 743) when it should be "FlattrimClicked()" (with not capital 'T'). making this change fixes the error.

Edit: I realized that I have also changed the lines that initialize the service clients "toggleCam_srv" and "flattrim_srv" (RosThread.cpp lines 188 and 189) to:

toggleCam_srv = nh_.serviceClient<std_srvs::Empty>(nh_.resolveName("ardrone/togglecam"));
flattrim_srv = nh_.serviceClient<std_srvs::Empty>(nh_.resolveName("ardrone/flattrim"));

I believe that just these three changes will get flat trim and toggle cam both working from the GUI.

Error in building TooN with gcc4.8 on Ubuntu 13.10

/home/lesire/work/r2d2/ardrone_ws/build/thirdparty/src/thirdparty/TooN/include/TooN/internal/allocator.hh:68:33: error: ‘debug_initialize’ was not declared in this scope, and no declarations were found by argument-dependent lookup at the point of instantiation [-fpermissive]
debug_initialize(my_data, Size);
^

Question about the code

I was revising the source code and I just noticed that in the function calcControl in autopilot/DroneController.cpp it appears to be implemented a PID controller. So, Why the yaw part uses just the proportional and the derivative part instead of using the integral part too? In DroneController.h it is even declared a variable named "Ki_yaw" which is never used in the .cpp. It is just used for the log.

"PTAM Drone Camera Feed" not showing

I'm trying to perform state estimation on the ardrone but whenever I launch the drone_stateestimation node, I get the "PTAM Drone Map View" window but the camera feed window doesn't show. Can someone suggest some possible solutions or maybe some things that I may have overlooked?

Trying to compile with cakin

Hi,
I followed the instructions in the README and get the following errors:

$ rosdep install tum_ardrone

ERROR: Rosdep cannot find all required resources to answer your query
Missing resource tum_ardrone
ROS path [0]=/opt/ros/hydro/share/ros
ROS path [1]=/opt/ros/hydro/share
ROS path [2]=/opt/ros/hydro/stacks

I tried running catkin_make anyway and I got this :

$ catkin_make
Base path: /home/alexandre/ros-ws
Source space: /home/alexandre/ros-ws/src
Build space: /home/alexandre/ros-ws/build
Devel space: /home/alexandre/ros-ws/devel
Install space: /home/alexandre/ros-ws/install
####
#### Running command: "cmake /home/alexandre/ros-ws/src -DCATKIN_DEVEL_PREFIX=/home/alexandre/ros-ws/devel -DCMAKE_INSTALL_PREFIX=/home/alexandre/ros-ws/install" in "/home/alexandre/ros-ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/alexandre/ros-ws/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/hydro
-- This workspace overlays: /opt/ros/hydro
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Python version: 2.7
-- Using Debian Python package layout
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/alexandre/ros-ws/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- catkin 0.5.86
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~  traversing 1 packages in topological order:
-- ~~  - tum_ardrone
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'tum_ardrone'
-- ==> add_subdirectory(tum_ardrone)
-- Using these message generators: gencpp;genlisp;genpy
-- tum_ardrone: 1 messages, 5 services
CMake Error at /usr/share/cmake-2.8/Modules/FindQt4.cmake:1216 (message):
  Found unsuitable Qt version "5.0.1" from /usr/bin/qmake, this code requires
  Qt 4.x
Call Stack (most recent call first):
  tum_ardrone/CMakeLists.txt:199 (find_package)


-- Configuring incomplete, errors occurred!
Invoking "cmake" failed

I'm on Ubuntu 13.04, using ROS Hydro. libqt4-dev is installed. I would also like to point out I'm new to ROS.

Thanks in advance

setMaxControl command is ignored

setMaxControl GUI command is unused, it is only assigned inside the Constructor of KIFlyTo class.

In order to cap the speed you need to modify "max_rp" "max_yaw" "max_gaz_rise" "max_gaz_drop" parameters of Autopilot with the dynamic reconfigure panel.

Getting PTAM point cloud

Is it possible to get and set in any way (maybe through a ros topic) information about the keypoint detected and used by PTAM algorithm?
This would be very helpful to save and reuse detected features without the need to reinitialize PTAM every time.

autopilot jumps to future waypoints.

Solved! See New Edits Below For Progress!

I am trying to get the ardrone to follow the path below:
screenshot from 2015-06-11 18 44 50

But while flying the ardrone jumps to a future waypoint and continues from there randomly.
Here is an example path that it took:
randompath

I analyzed the way-points that it sent to the autopilot and noticed that in one flight it went from these two points:
New Target: xyz = -2.062, -2.289, 1.905, yaw=8.581
New Target: xyz = 4.375, -0.039, 1.905, yaw=8.581

Whereas those points, looking at the waypoint file, correspond to lines 48 and 131. So the autopilot skipped the points in between.

Line 48 of Waypoint file: goto -2.25 -2.25 2.0 0
Line 131 of Waypoint file: goto 4.75 0 2.0 0

How should I fix this issue?
Is there a known place in the code where the autopilot calculates the new waypoint? or perhaps a place where it reads the next waypoint?

EDIT 1:
I first though that the minPublishFrequency was causing the issue since state estimator gave the following message: "0.246477s between two consecutive navinfos. This system requires Navinfo at 200Hz. If this error persists, set drone to debug mode and change publish freq in ardrone_autonomy"

But then I realized that if the waypoint file has more waypoints than ~70ish, the queue that takes in the waypoints (can be seen under the Autopilot status menu in the GUI) misses some of the waypoints when it is reading them in from the text file. When I hit clear and send, sometimes I see the right amount of waypoints stored into the queue (%30) and at other times it is always less (%70).
This is really weird. Do other people also get this issue?

EDIT 2:
Adding a print line in the RosThread::publishCommand(std::string c) function acts as a delay and all waypoints get pushed to the queue. I think a delay needs to be added or the ros publish queue needs to be extended for waypoints of size>70 to work properly.

Update documentation

I have started a branch (doc-markdown) to update the doc for the last version, using catkin for install, and a detail of all nodes as done on standard ROS packages.
This doc uses Markdown.

Feel free to contribute!

Error with catkin_make after install tum_ardrone

Hi,
I have this configuration:
ROS version: Indigo 1.11.9
OS version: Ubuntu 14.04 64 bits
gcc version 4.8.2 (Ubuntu 4.8.2-19ubuntu1)

I follow this instructions of https://github.com/tum-vision/tum_ardrone

cd catkin_ws/src
git clone https://github.com/tum-vision/tum_ardrone.git -b indigo-devel
cd ..
rosdep install tum_ardrone
catkin_make

and I received this message after 83%:
...
Building ARDroneTool/Lib
/usr/bin/ld: no se puede encontrar -lglut
collect2: error: ld returned 1 exit status
make[2]: *** [/home/rafagarcia0810/catkin_ws/devel/lib/tum_ardrone/drone_stateestimation] Error 1
make[1]: *** [tum_ardrone/CMakeFiles/drone_stateestimation.dir/all] Error 2
make[1]: *** Se espera a que terminen otras tareas....
Building ARDroneTool/Lib
[ 84%] Performing install step for 'ardronelib'
make[3]: atención: el servidor de tareas no está disponible: se utilizará -j1. Añada `+' a la regla padre del make.
[ 84%] Completed 'ardronelib'
[ 86%] Built target ardronelib
make: *** [all] Error 2
Invoking "make" failed

someone know how I can fix it?
thanks.

impossible to compile tum_ardrone

When I build (cmd : rosmake), I have this errors

[ 77%] Built target drone_stateestimation
/opt/ros/groovy/tum_ardrone/src/UINode/RosThread.cpp: In member function ‘void RosThread::navdataCb(ardrone_autonomy::NavdataConstPtr)’:
/opt/ros/groovy/tum_ardrone/src/UINode/RosThread.cpp:88:24: error: ‘const struct ardrone_autonomy::Navdata_std::allocator’ has no member named ‘motor1’
/opt/ros/groovy/tum_ardrone/src/UINode/RosThread.cpp:89:24: error: ‘const struct ardrone_autonomy::Navdata_std::allocator’ has no member named ‘motor2’
/opt/ros/groovy/tum_ardrone/src/UINode/RosThread.cpp:90:24: error: ‘const struct ardrone_autonomy::Navdata_std::allocator’ has no member named ‘motor3’
/opt/ros/groovy/tum_ardrone/src/UINode/RosThread.cpp:91:24: error: ‘const struct ardrone_autonomy::Navdata_std::allocator’ has no member named ‘motor4’
make[4]: *** [CMakeFiles/drone_gui.dir/src/UINode/RosThread.cpp.o] Error 1
make[4]: Leaving directory /opt/ros/groovy/tum_ardrone/build' make[3]: *** [CMakeFiles/drone_gui.dir/all] Error 2 make[3]: Leaving directory/opt/ros/groovy/tum_ardrone/build'
make[2]: *** [all] Error 2
make[2]: Leaving directory /opt/ros/groovy/tum_ardrone/build' make[1]: *** [all] Error 2 make[1]: Leaving directory/opt/ros/groovy/tum_ardrone'

Any Idea ?

Problem in the code

I have written code to issue the command to /tum_ardrone/com topic will running drone_autopilot and drone_stateestimation. I have written followings simple code which just take off and land the drone. When I echoed /tum_ardrone/com while issuing commands through GUI, I found same string commands as given below in the code.

std_msgs::String cpp2ros(std::string in) {
    std_msgs::String out;
    out.data = in;
    return out;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "tumdrone");

    ros::NodeHandle tumdrone;

    cv::Mat image = cv::imread("/home/ameerhamzakhan/image.jpg");
    cv::imshow("Image", image);

    ros::Publisher pubCommand = tumdrone.advertise<std_msgs::String>("/tum_ardrone/com", 100);

    char commandKey = 0;

    while(ros::ok()) {
        if(commandKey == 'q') {
            pubCommand.publish(cpp2ros("u l Autopilot: Cleared Command Queue"));

            pubCommand.publish(cpp2ros("u l Autopilot: Start Controlling"));

            pubCommand.publish(cpp2ros("c clearCommands"));

            pubCommand.publish(cpp2ros("c takeoff"));

            pubCommand.publish(cpp2ros("c land"));
        }

        commandKey = cv::waitKey(1);
    }

    return 0;
}

Here I am using openCV image just to monitor 'q' key presses because I find it convenient this way, and it has nothing to do with the rest of code.

Yaw causes the localization system to lose tracking

The system is accurate when translating, but yaw causes the drone to lose all tracking, even though there are many features. It tells me that it is "attempting recovery".

Specifically, new keypoints are not added to the map.

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.