Skip to content

Commit 7565380

Browse files
Fix various documentation errors in tf2 (backport #857) (#864)
Generated-by: Portions of this commit may include code completion from github.copilot version 1.372.0 or later Signed-off-by: R Kent James <[email protected]> Co-authored-by: Alejandro Hernandez Cordero <[email protected]> (cherry picked from commit 054b809)
1 parent 4224b81 commit 7565380

File tree

5 files changed

+22
-33
lines changed

5 files changed

+22
-33
lines changed

tf2/Doxyfile

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,4 +20,5 @@ MACRO_EXPANSION = YES
2020
EXPAND_ONLY_PREDEF = YES
2121
PREDEFINED += TF2_PUBLIC=
2222
PREDEFINED += TF2SIMD_FORCE_INLINE=
23-
PREDEFINED += ATTRIBUTE_ALIGNED16(class)=
23+
PREDEFINED += ATTRIBUTE_ALIGNED16(class)=class
24+
EXCLUDE_PATTERNS = */test/*

tf2/include/tf2/LinearMath/Matrix3x3.hpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class Matrix3x3 {
3636
Vector3 m_el[3];
3737

3838
public:
39-
/** @brief No initializaion constructor */
39+
/** @brief No initialization constructor */
4040
TF2_PUBLIC
4141
Matrix3x3 () {}
4242

@@ -281,7 +281,8 @@ class Matrix3x3 {
281281
/**@brief Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR
282282
* @param yaw Yaw around Z axis
283283
* @param pitch Pitch around Y axis
284-
* @param roll around X axis */
284+
* @param roll around X axis
285+
* @param solution_number Which solution of two possible solutions (1 or 2) are possible values */
285286
TF2_PUBLIC
286287
void getEulerYPR(tf2Scalar& yaw, tf2Scalar& pitch, tf2Scalar& roll, unsigned int solution_number = 1) const
287288
{
@@ -411,8 +412,8 @@ class Matrix3x3 {
411412
* @param rot stores the rotation from the coordinate system in which the matrix is diagonal to the original
412413
* coordinate system, i.e., old_this = rot * new_this * rot^T.
413414
* @param threshold See iteration
414-
* @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied
415-
* by the sum of the absolute values of the diagonal, or when maxSteps have been executed.
415+
* @param maxSteps The iteration stops when all off-diagonal elements are less than the threshold multiplied
416+
* by the sum of the absolute values of the diagonal, or when maxSteps have been executed.
416417
*
417418
* Note that this matrix is assumed to be symmetric.
418419
*/
@@ -501,8 +502,8 @@ class Matrix3x3 {
501502
/**@brief Calculate the matrix cofactor
502503
* @param r1 The first row to use for calculating the cofactor
503504
* @param c1 The first column to use for calculating the cofactor
504-
* @param r1 The second row to use for calculating the cofactor
505-
* @param c1 The second column to use for calculating the cofactor
505+
* @param r2 The second row to use for calculating the cofactor
506+
* @param c2 The second column to use for calculating the cofactor
506507
* See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details
507508
*/
508509
TF2_PUBLIC

tf2/include/tf2/LinearMath/Vector3.hpp

Lines changed: 3 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3
8787
}
8888

8989
/**@brief Add a vector to this one
90-
* @param The vector to add to this one */
90+
* @param v The vector to add to this one */
9191
TF2SIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
9292
{
9393

@@ -96,8 +96,8 @@ ATTRIBUTE_ALIGNED16(class) Vector3
9696
}
9797

9898

99-
/**@brief Sutf2ract a vector from this one
100-
* @param The vector to sutf2ract */
99+
/**@brief Subtract a vector from this one
100+
* @param v The vector to subtract */
101101
TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
102102
{
103103
m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
@@ -586,23 +586,7 @@ class tf2Vector4 : public Vector3
586586
return absolute4().maxAxis4();
587587
}
588588

589-
590-
591589

592-
/**@brief Set x,y,z and zero w
593-
* @param x Value of x
594-
* @param y Value of y
595-
* @param z Value of z
596-
*/
597-
598-
599-
/* void getValue(tf2Scalar *m) const
600-
{
601-
m[0] = m_floats[0];
602-
m[1] = m_floats[1];
603-
m[2] =m_floats[2];
604-
}
605-
*/
606590
/**@brief Set the values
607591
* @param x Value of x
608592
* @param y Value of y

tf2/include/tf2/buffer_core.hpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -163,12 +163,15 @@ class BufferCore : public BufferCoreInterface
163163
const std::string & tracking_frame, const std::string & observation_frame,
164164
const TimePoint & time, const tf2::Duration & averaging_interval) const;
165165

166-
/** \brief Lookup the velocity of the moving_frame in the reference_frame
167-
* \param reference_frame The frame in which to track
168-
* \param moving_frame The frame to track
166+
/** \brief Lookup the velocity of the tracking_frame with respect to the observation frame in the reference_frame using the reference point.
167+
* \param tracking_frame The frame in which to track
168+
* \param observation_frame The frame to track
169+
* \param reference_frame The frame in which to express the velocity
170+
* \param reference_point The point in the reference_frame at which to compute the velocity
171+
* \param reference_point_frame The frame in which the reference_point is expressed
169172
* \param time The time at which to get the velocity
170173
* \param duration The period over which to average
171-
* \param velocity The velocity output
174+
* \return The velocity output
172175
*
173176
* Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException,
174177
* TransformReference::MaxDepthException

tf2/include/tf2/convert.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,9 +48,9 @@ namespace tf2
4848
/**\brief The templated function expected to be able to do a transform
4949
*
5050
* This is the method which tf2 will use to try to apply a transform for any given datatype.
51-
* \param data_in[in] The data to be transformed.
52-
* \param data_out[inout] A reference to the output data. Note this can point to data in and the method should be mutation safe.
53-
* \param transform[in] The transform to apply to data_in to fill data_out.
51+
* \param[in] data_in The data to be transformed.
52+
* \param[in,out] data_out A reference to the output data. Note this can point to data in and the method should be mutation safe.
53+
* \param[in] transform The transform to apply to data_in to fill data_out.
5454
*
5555
* This method needs to be implemented by client library developers
5656
*/

0 commit comments

Comments
 (0)