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
The code for transforming a vector does not apply the translation but only rotation.
/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
* \param t_in The vector to transform, as a Vector3 message.
* \param t_out The transformed vector, as a Vector3 message.
* \param transform The timestamped transform to apply, as a TransformStamped message.
*/
template <>
inline
void doTransform(const geometry_msgs::Vector3& t_in, geometry_msgs::Vector3& t_out, const geometry_msgs::TransformStamped& transform)
{
tf2::Transform t;
fromMsg(transform.transform, t);
tf2::Vector3 v_out = t.getBasis() * tf2::Vector3(t_in.x, t_in.y, t_in.z);
t_out.x = v_out[0];
t_out.y = v_out[1];
t_out.z = v_out[2];
}
The line performing the transformation must be changed to:
tf2::Vector3 v_out = t * tf2::Vector3(t_in.x, t_in.y, t_in.z);
Like this it will use the overloaded operator* of transform and properly transform the vector.
The text was updated successfully, but these errors were encountered:
I just found out it seems to be intended like this, according to issue #124
It is fairly misleading though and could also be mentioned in the function description.
This is intentional Vector and Points have different semantic meanings, that's why they have different classes. This difference is the primary one, they have magnitude and direction but are always from the origin.
seanyen
pushed a commit
to ms-iot/geometry2
that referenced
this issue
Dec 25, 2020
… (ros#330)
* Clear callback from transformable_callbacks_ when callback is done or not needed
Co-authored-by: marting87 <martinganeff@gmail.com>
Co-authored-by: Matthijs den Toom <mdentoom@lely.com>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
The code for transforming a vector does not apply the translation but only rotation.
The line performing the transformation must be changed to:
Like this it will use the overloaded operator* of transform and properly transform the vector.
The text was updated successfully, but these errors were encountered: