Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changing parameters will now affect the drone, rather than doing nothing! #26

Closed
wants to merge 24 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
d1d4cd1
.gitignore results of build operation and added launch file
Nov 7, 2012
4f568c1
Bug Fix
Nov 9, 2012
b5c57a3
Launch file moved to its own folder. README updated for launch file.
mani-monaj Nov 10, 2012
0b58364
Add backward compatibilty support for -ip command line argument
mani-monaj Nov 10, 2012
0dc6a2a
Manually merging #25 to add magnetometer topic (by @sameerparekh)
mani-monaj Nov 10, 2012
3ec0db0
will now only read rosparams for writeable drone parameters
Nov 12, 2012
699fa5a
Revert "will now only read rosparams for writeable drone parameters"
mikehamer Nov 12, 2012
b72793b
Will now only read rosparams for writeable drone parameters
mikehamer Nov 12, 2012
d1de363
A more sensible launch file for most people
mikehamer Nov 12, 2012
712a24b
Fixed launch file
mikehamer Nov 12, 2012
73e9a53
Information about branch added to the README
mani-monaj Nov 12, 2012
13bb31f
Minor formatting
mani-monaj Nov 12, 2012
5d48b4d
Updated README to include tm format
mikehamer Nov 13, 2012
13145dc
Merge pull request #27 from mikehamer/master
mani-monaj Nov 14, 2012
efaa64c
Added custom navdata messages and message generator
mikehamer Nov 14, 2012
f46a7ad
NOT FINISHED: Incorporating custom messages into code
mikehamer Nov 14, 2012
2fc267c
Revert "NOT FINISHED: Incorporating custom messages into code"
mikehamer Nov 16, 2012
ca5fadf
Added custom messages and handling code
mikehamer Nov 21, 2012
54d6fff
Enabling all messages
mikehamer Nov 21, 2012
24529cd
Added the ability to disable hover mode and constantly send commands
mikehamer Nov 21, 2012
1b7074d
Added enable_legacy_navdata (true by default)
mikehamer Nov 21, 2012
0c42f25
No more cache stuff!
mikehamer Nov 21, 2012
96a7a48
Merge branch 'more-navdata'
mikehamer Nov 21, 2012
4057b6e
Updated to include some new flags and enable more aggressive flight
mikehamer Nov 21, 2012
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 17 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@
*.lo
*.o

# Project Files
*.sublime-workspace
*.sublime-project

# Compiled Dynamic libraries
*.so

Expand All @@ -12,4 +16,16 @@
*.a
/nbproject/private/
Makefile
/build/CMakeFiles/
/build/CMakeFiles/

# Build results
/ARDroneLib/FFMPEG/Includes
/ARDroneLib/FFMPEG/FFMPEG
/ARDroneLib/Soft/Build/
/ARDroneLib/Soft/Common/generated_custom.h
/bin
/build/
/msg_gen
/srv_gen
/src/ardrone_autonomy
scripts/cache/DEBS_avail
30 changes: 14 additions & 16 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

### Updates

- *November 9 2012*: Critical Bug in sending configurations to drone fixed ([More info](https://github.com/AutonomyLab/ardrone_autonomy/issues/24)). Seperate topic for magnetometer data added ([More info](https://github.com/AutonomyLab/ardrone_autonomy/pull/25)).
- *September 5 2012*: Experimental automatic IMU bias removal.
- *August 27 2012*: Thread-safe SDK data access. Synchronized `navdata` and `camera` topics.
- *August 20 2012*: The driver is now provides ROS standard camera interface.
Expand Down Expand Up @@ -33,6 +34,8 @@ The installation follows the same steps needed usually to compile a ROS driver.
$ roscd ardrone_autonomy
```

**NOTE (For advanced users):** Instead of the `master` branch you can use the `dev-unstable` branch for the latest _unstable_ code which may contain bug fixes or new features. This is the branch that all developments happen on. Please use this branch to submit pull requests.

* Compile the AR-Drone SDK: The driver contains a slightly patched version of AR-Drone 2.0 SDK which is located in `ARDroneLib` directory. To compile it, execute the `./build_sdk.sh`. Any system-wide dependency will be managed by the SDK's build script. You may be asked to install some packages during the installation procedure (e.g `daemontools`). You can verify the success of the SDK's build by checking the `lib` folder.

```bash
Expand Down Expand Up @@ -85,12 +88,16 @@ Information received from the drone will be published to the `ardrone/navdata` t
* `altd`: Estimated altitude (mm)
* `vx`, `vy`, `vz`: Linear velocity (mm/s) [TBA: Convention]
* `ax`, `ay`, `az`: Linear acceleration (g) [TBA: Convention]
* `tm`: Timestamp of the data returned by the Drone
* `tm`: Timestamp of the data returned by the Drone returned as a packed uint32 (sec:11; usec:21)

### IMU data

The linear acceleration, angular velocity and orientation from the `Navdata` is also published to a standard ROS [`sensor_msgs/Imu`](http://www.ros.org/doc/api/sensor_msgs/html/msg/Imu.html) message. The units are all metric and the reference frame is in `Base` frame. This topic is experimental. The covariance values are specified by specific parameters.

### Megnetometer Data

The normalized magnetometer readings are also published to `ardrone/mag` topic as a standard ROS [`geometry_msgs/Vector3Stamped`](http://www.ros.org/doc/api/geometry_msgs/html/msg/Vector3Stamped.html) message.

### Cameras

Both AR-Drone 1.0 and 2.0 are equipped with two cameras. One frontal camera pointing forward and one vertical camera pointing downward. This driver will create three topics for each drone: `ardrone/image_raw`, `ardrone/front/image_raw` and `ardrone/bottom/image_raw`. Each of these three are standard [ROS camera interface](http://ros.org/wiki/camera_drivers) and publish messages of type [image transport](http://www.ros.org/wiki/image_transport). The driver is also a standard [ROS camera driver](http://www.ros.org/wiki/camera_drivers), therefor if camera calibration information is provided either as a set of ROS parameters or appropriate `ardrone_front.yaml` and/or `ardrone_bottom.yaml`, the information will be published in appropriate `camera_info` topics. Please check the FAQ section for more information.
Expand Down Expand Up @@ -208,16 +215,20 @@ The Parrot's license, copyright and disclaimer for `ARDroneLib` are included wit

## Contributors

- [Rachel Brindle](https://github.com/younata) - [Enhanced Navdata for AR-Drone 2.0](https://github.com/AutonomyLab/ardrone_autonomy/pull/2)
- [Mike Hamer](https://github.com/mikehamer) - Added support for proper SDK2 way of configuring the Drone via parameter (critical bug fix). [More Info](https://github.com/AutonomyLab/ardrone_autonomy/pull/26)
- [Sameer Parekh](https://github.com/sameerparekh) - [Seperate Magnetometer Topic](https://github.com/AutonomyLab/ardrone_autonomy/pull/25)
- [Devmax](https://github.com/devmax) - [Flat Trim](https://github.com/AutonomyLab/ardrone_autonomy/issues/18) + Various
comments for enhancements
- [Rachel Brindle](https://github.com/younata) - [Enhanced Navdata for AR-Drone 2.0](https://github.com/AutonomyLab/ardrone_autonomy/pull/2)

## FAQ

### How can I report a bug, submit patches or ask for a feature?

`github` offers a nice and convenient issue tracking and social coding platform, it can be used for bug reports and pull/feature request. This is the preferred method. You can also contact the author directly.

If you want to submit a pull request, please submit to `dev-unstable` branch.

### Why the `ARDroneLib` has been patched?

The ARDrone 2.0 SDK has been patched to 1) Enable the lib only build 2) Make its command parsing compatible with ROS and 3) To fix its weird `main()` function issue
Expand Down Expand Up @@ -279,20 +290,7 @@ After successful calibration, press the `commit` button in the UI. The driver wi

### Can I see a sample ardrone node in a launch file to learn how to set parameters?


```xml

<node name="ardrone_driver" pkg="ardrone_autonomy" type="ardrone_driver" output="screen">
<param name="max_bitrate" value="2000" />
<param name="bitrate" value="2000" />
<param name="do_imu_caliberation" value="true" />
<param name="tf_prefix" value="mydrone" />
<!-- Covariance Values (3x3 matrices reshaped to 1x9)-->
<rosparam param="cov/imu_la">[0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]</rosparam>
<rosparam param="cov/imu_av">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="cov/imu_or">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 100000.0]</rosparam>
</node>
```
Yes, you can check the `launch` folder for sample lanuch file.

## TODO

Expand Down
64 changes: 64 additions & 0 deletions launch/ardrone.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
<!-- This is a sample lanuch file, please change it based on your needs -->
<launch>
<node name="ardrone_driver" pkg="ardrone_autonomy" type="ardrone_driver" output="screen" clear_params="true">
<param name="outdoor" value="1" />
<param name="flight_without_shell" value="1" />
<param name="navdata_demo" value="0" />

<param name="max_bitrate" value="2000" />
<param name="bitrate" value="2000" />
<param name="video_codec" value="129" />

<param name="altitude_max" value="5000" />
<param name="altitude_min" value="300" />

<param name="control_vz_max" value="2000" />
<param name="control_yaw" value="6.11" />
<param name="euler_angle_max" value="0.35" />

<param name="detect_type" value="10" />
<param name="detections_select_h" value="128" />
<param name="detections_select_v_hsync" value="32" />
<param name="enemy_colors" value="3" />
<param name="enemy_without_shell" value="0" />
<param name="do_imu_caliberation" value="false" />
<param name="tf_prefix" value="mydrone" />

<param name="command_disable_hover" value="true" />
<param name="command_always_send" value="true" />

<param name="enable_navdata_demo" value="true" />
<param name="enable_navdata_time" value="true" />
<param name="enable_navdata_raw_measures" value="true" />
<param name="enable_navdata_phys_measures" value="true" />
<param name="enable_navdata_gyros_offsets" value="true" />
<param name="enable_navdata_euler_angles" value="true" />
<param name="enable_navdata_references" value="true" />
<param name="enable_navdata_trims" value="true" />
<param name="enable_navdata_rc_references" value="true" />
<param name="enable_navdata_pwm" value="true" />
<param name="enable_navdata_altitude" value="true" />
<param name="enable_navdata_vision_raw" value="true" />
<param name="enable_navdata_vision_of" value="true" />
<param name="enable_navdata_vision" value="true" />
<param name="enable_navdata_vision_perf" value="true" />
<param name="enable_navdata_trackers_send" value="true" />
<param name="enable_navdata_vision_detect" value="true" />
<param name="enable_navdata_watchdog" value="true" />
<param name="enable_navdata_adc_data_frame" value="true" />
<param name="enable_navdata_video_stream" value="true" />
<param name="enable_navdata_games" value="true" />
<param name="enable_navdata_pressure_raw" value="true" />
<param name="enable_navdata_magneto" value="true" />
<param name="enable_navdata_wind_speed" value="true" />
<param name="enable_navdata_kalman_pressure" value="true" />
<param name="enable_navdata_hdvideo_stream" value="true" />
<param name="enable_navdata_wifi" value="true" />
<param name="enable_navdata_zimmu_3000" value="true" />

<!-- Covariance Values (3x3 matrices reshaped to 1x9)-->
<rosparam param="cov/imu_la">[0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]</rosparam>
<rosparam param="cov/imu_av">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="cov/imu_or">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 100000.0]</rosparam>
</node>
</launch>
9 changes: 9 additions & 0 deletions msg/matrix33.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
float32 m11
float32 m12
float32 m13
float32 m21
float32 m22
float32 m23
float32 m31
float32 m32
float32 m33
6 changes: 6 additions & 0 deletions msg/navdata_adc_data_frame.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 version
uint8[] data_frame
14 changes: 14 additions & 0 deletions msg/navdata_altitude.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
Header header
float64 drone_time
uint16 tag
uint16 size
int32 altitude_vision
float32 altitude_vz
int32 altitude_ref
int32 altitude_raw
float32 obs_accZ
float32 obs_alt
vector31 obs_x
uint32 obs_state
vector21 est_vb
uint32 est_state
15 changes: 15 additions & 0 deletions msg/navdata_demo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 ctrl_state
uint32 vbat_flying_percentage
float32 theta
float32 phi
float32 psi
int32 altitude
float32 vx
float32 vy
float32 vz
uint32 num_frames
uint32 detection_camera_type
6 changes: 6 additions & 0 deletions msg/navdata_euler_angles.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
Header header
float64 drone_time
uint16 tag
uint16 size
float32 theta_a
float32 phi_a
6 changes: 6 additions & 0 deletions msg/navdata_games.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 double_tap_counter
uint32 finish_line_counter
5 changes: 5 additions & 0 deletions msg/navdata_gyros_offsets.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Header header
float64 drone_time
uint16 tag
uint16 size
float32[] offset_g
11 changes: 11 additions & 0 deletions msg/navdata_hdvideo_stream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 hdvideo_state
uint32 storage_fifo_nb_packets
uint32 storage_fifo_size
uint32 usbkey_size
uint32 usbkey_freespace
uint32 frame_number
uint32 usbkey_remaining_time
21 changes: 21 additions & 0 deletions msg/navdata_kalman_pressure.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
Header header
float64 drone_time
uint16 tag
uint16 size
float32 offset_pressure
float32 est_z
float32 est_zdot
float32 est_bias_PWM
float32 est_biais_pression
float32 offset_US
float32 prediction_US
float32 cov_alt
float32 cov_PWM
float32 cov_vitesse
int32 bool_effet_sol
float32 somme_inno
int32 flag_rejet_US
float32 u_multisinus
float32 gaz_altitude
int32 Flag_multisinus
int32 Flag_multisinus_debut
18 changes: 18 additions & 0 deletions msg/navdata_magneto.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
Header header
float64 drone_time
uint16 tag
uint16 size
int16 mx
int16 my
int16 mz
vector31 magneto_raw
vector31 magneto_rectified
vector31 magneto_offset
float32 heading_unwrapped
float32 heading_gyro_unwrapped
float32 heading_fusion_unwrapped
uint8 magneto_calibration_ok
uint32 magneto_state
float32 magneto_radius
float32 error_mean
float32 error_var
11 changes: 11 additions & 0 deletions msg/navdata_phys_measures.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
Header header
float64 drone_time
uint16 tag
uint16 size
float32 accs_temp
uint16 gyro_temp
float32[] phys_accs
float32[] phys_gyros
uint32 alim3V3
uint32 vrefEpson
uint32 vrefIDG
8 changes: 8 additions & 0 deletions msg/navdata_pressure_raw.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
Header header
float64 drone_time
uint16 tag
uint16 size
int32 up
int16 ut
int32 Temperature_meas
int32 Pression_meas
29 changes: 29 additions & 0 deletions msg/navdata_pwm.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
Header header
float64 drone_time
uint16 tag
uint16 size
uint8 motor1
uint8 motor2
uint8 motor3
uint8 motor4
uint8 sat_motor1
uint8 sat_motor2
uint8 sat_motor3
uint8 sat_motor4
float32 gaz_feed_forward
float32 gaz_altitude
float32 altitude_integral
float32 vz_ref
int32 u_pitch
int32 u_roll
int32 u_yaw
float32 yaw_u_I
int32 u_pitch_planif
int32 u_roll_planif
int32 u_yaw_planif
float32 u_gaz_planif
uint16 current_motor1
uint16 current_motor2
uint16 current_motor3
uint16 current_motor4
float32 altitude_der
19 changes: 19 additions & 0 deletions msg/navdata_raw_measures.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
Header header
float64 drone_time
uint16 tag
uint16 size
int16[] raw_gyros
int16[] raw_gyros_110
uint32 vbat_raw
uint16 us_debut_echo
uint16 us_fin_echo
uint16 us_association_echo
uint16 us_distance_echo
uint16 us_courbe_temps
uint16 us_courbe_valeur
uint16 us_courbe_ref
uint16 flag_echo_ini
uint16 nb_echo
uint32 sum_echo
int32 alt_temp_raw
int16 gradient
9 changes: 9 additions & 0 deletions msg/navdata_rc_references.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
Header header
float64 drone_time
uint16 tag
uint16 size
int32 rc_ref_pitch
int32 rc_ref_roll
int32 rc_ref_yaw
int32 rc_ref_gaz
int32 rc_ref_ag
Loading