bottom cam tf error in ardrone_autonomy [closed]
Hi all,
As far as I understand, there is a problem with the transform of base to bottom_cam in ardrone_autonomy. The problem is as follows: In ardrone_driver.cpp around line 92~97 we see the following code.
// Bottom Cam to Base (Bad Assumption: No translation from IMU and Base)
// TODO: This should be different from Drone 1 & 2.
tf_base_bottom = tf::StampedTransform(
tf::Transform(
tf::createQuaternionFromRPY(180.0 * _DEG2RAD, 0.0, 90.0 * _DEG2RAD),
tf::Vector3(0.0, -0.02, 0.0)),
ros::Time::now(), droneFrameBase, droneFrameBottomCam
);
1) The above rotation makes the x-axis of the bottom_cam point towards the y-axis of the ardrone_base_link while the y-axis of the bottom_cam point towards the x-axis of the ardrone_base_link. This gives trouble if the bottom_cam observe, for instance, a marker like alvar (ar_track_alvar) which is aligned with the ardrone_base_link; it makes the forward and backward reversed.
2) I guess the translation in the negative Y direction is also wrong. May be it should be in the negative Z direction from the ardrone_base_link
3) Just a minor matter: the comment should also be corrected to Base to Bottom cam (not bottom to base).
So, I suggest
tf_base_bottom = tf::StampedTransform(
tf::Transform(
//tf::createQuaternionFromRPY(180.0 * _DEG2RAD, 0.0, 90.0 * _DEG2RAD),
tf::createQuaternionFromRPY(-180.0 * _DEG2RAD, 0, -90.0 * _DEG2RAD),
//tf::Vector3(0.0, -0.02, 0.0)),
tf::Vector3(0.0, 0.0, -0.02)),
ros::Time::now(), droneFrameBase, droneFrameBottomCam
);
By the way, there was a similar question at link
Thank you
CS