AutonomyLab / ardrone_autonomy

ROS driver for Parrot AR-Drone 1.0 and 2.0 quadrocopters
http://wiki.ros.org/ardrone_autonomy
BSD 3-Clause "New" or "Revised" License
356 stars 226 forks source link

Front camera #108

Closed hsoltani closed 9 years ago

hsoltani commented 10 years ago

Hi I took out the front camera of AR.Drone and mounted on the bottom of the drone looking downwards. Should I change anything on ardrone_autonomy package (such as rotation matrix,...) for this situation?

mani-monaj commented 10 years ago

Yes, you need to change the tf transformation between base_link and front_camera. I suggest that you change this line of the file src/ardrone_driver.cpp.

From:

tf::createQuaternionFromRPY(-90.0 * _DEG2RAD, 0.0, -90.0 * _DEG2RAD),

To something like this:

 tf::createQuaternionFromRPY(-90.0 * _DEG2RAD, 0.0, -90.0 * _DEG2RAD) * tf::createQuaternionFromRPY(frontCamRotation * _DEG2RAD, 0.0, 0.0),

Assuming that you only pitched the camera downwards. If you made other rotations, you need to change the second term respectively. There is a sample implementation of this idea in autolab branch (src/ardrone_driver.cpp). The code is outdated though.