You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I tried to attach a camera to the end of the pendulum link and the result was not as expected. After reviewing the sample code in the FAQ (which is the same than the one in cameras.py), I figured out a bug. Here is the original proposed code:
tf=dartpy.math.Isometry3()
rot=dartpy.math.AngleAxis(3.14, [1., 0., 0.])
rot=rot.multiply( dartpy.math.AngleAxis(1.57, [0., 0., 1.])).to_rotation_matrix()
tf.set_translation([0., 0., 0.1])
camera.attach_to_body(robot.body_node("iiwa_link_ee"), tf) # cameras are looking towards -z by default
For the C++ version, we have:
Eigen::Isometry3d tf;
tf = Eigen::AngleAxisd(3.14, Eigen::Vector3d{1., 0., 0.});
tf *= Eigen::AngleAxisd(1.57, Eigen::Vector3d{0., 0., 1.});
tf.translation() = Eigen::Vector3d(0., 0., 0.1);
camera->attach_to_body(robot->body_node("iiwa_link_ee"), tf); // cameras are looking towards -z by default
In the C++ version, we can see that tf is initialized with the rotation parameters, which is not the case in the Python version. Then, the Python version created the rot matrix to adjust the orientation of the camera (I think it is to compensate that camera looks towards the -z axis), but it does not use it! Thus, I added the following line in the code between the two last lines, and the result looked as expected:
tf.set_rotation(rot)
Can you confirm my patch is correct and update the example and doc accordingly?
Last question: why do you need to move the camera of 0.1 on the z axis? Is it to be a little bit more far from the node to avoid some kind of artifact if we put the camera exactly on the node?
The text was updated successfully, but these errors were encountered:
Hi @costashatz, here is an issue associated to the Joss review openjournals/joss-reviews#6771
I tried to attach a camera to the end of the pendulum link and the result was not as expected. After reviewing the sample code in the FAQ (which is the same than the one in
cameras.py
), I figured out a bug. Here is the original proposed code:For the C++ version, we have:
In the C++ version, we can see that
tf
is initialized with the rotation parameters, which is not the case in the Python version. Then, the Python version created therot
matrix to adjust the orientation of the camera (I think it is to compensate that camera looks towards the-z
axis), but it does not use it! Thus, I added the following line in the code between the two last lines, and the result looked as expected:Can you confirm my patch is correct and update the example and doc accordingly?
Last question: why do you need to move the camera of 0.1 on the
z
axis? Is it to be a little bit more far from the node to avoid some kind of artifact if we put the camera exactly on the node?The text was updated successfully, but these errors were encountered: