diff --git a/tf2_eigen/include/tf2_eigen/tf2_eigen.h b/tf2_eigen/include/tf2_eigen/tf2_eigen.h index c7e3cc79e..00c789ba7 100644 --- a/tf2_eigen/include/tf2_eigen/tf2_eigen.h +++ b/tf2_eigen/include/tf2_eigen/tf2_eigen.h @@ -215,10 +215,10 @@ void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped(out)); } -/** \brief Apply a geometry_msgs Transform to a Eigen-specific affine transform data type. +/** \brief Apply a geometry_msgs Transform to an Eigen Affine3d transform. * This function is a specialization of the doTransform template defined in tf2/convert.h, * although it can not be used in tf2_ros::BufferInterface::transform because this - * functions rely on the existence of a time stamp and a frame id in the type which should + * function relies on the existence of a time stamp and a frame id in the type which should * get transformed. * \param t_in The frame to transform, as a Eigen Affine3d transform. * \param t_out The transformed frame, as a Eigen Affine3d transform. @@ -438,10 +438,10 @@ void fromMsg(const geometry_msgs::Twist &msg, Eigen::Matrix& out) { out[5] = msg.angular.z; } -/** \brief Apply a geometry_msgs TransformStamped to a Eigen-specific affine transform data type. +/** \brief Apply a geometry_msgs TransformStamped to an Eigen Affine3d transform. * This function is a specialization of the doTransform template defined in tf2/convert.h, * although it can not be used in tf2_ros::BufferInterface::transform because this - * functions rely on the existence of a time stamp and a frame id in the type which should + * function relies on the existence of a time stamp and a frame id in the type which should * get transformed. * \param t_in The frame to transform, as a timestamped Eigen Affine3d transform. * \param t_out The transformed frame, as a timestamped Eigen Affine3d transform.