Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion tf2/Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -20,4 +20,5 @@ MACRO_EXPANSION = YES
EXPAND_ONLY_PREDEF = YES
PREDEFINED += TF2_PUBLIC=
PREDEFINED += TF2SIMD_FORCE_INLINE=
PREDEFINED += ATTRIBUTE_ALIGNED16(class)=
PREDEFINED += ATTRIBUTE_ALIGNED16(class)=class
EXCLUDE_PATTERNS = */test/*
13 changes: 7 additions & 6 deletions tf2/include/tf2/LinearMath/Matrix3x3.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class Matrix3x3 {
Vector3 m_el[3];

public:
/** @brief No initializaion constructor */
/** @brief No initialization constructor */
TF2_PUBLIC
Matrix3x3 () {}

Expand Down Expand Up @@ -281,7 +281,8 @@ class Matrix3x3 {
/**@brief Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR
* @param yaw Yaw around Z axis
* @param pitch Pitch around Y axis
* @param roll around X axis */
* @param roll around X axis
* @param solution_number Which solution of two possible solutions (1 or 2) are possible values */
TF2_PUBLIC
void getEulerYPR(tf2Scalar& yaw, tf2Scalar& pitch, tf2Scalar& roll, unsigned int solution_number = 1) const
{
Expand Down Expand Up @@ -411,8 +412,8 @@ class Matrix3x3 {
* @param rot stores the rotation from the coordinate system in which the matrix is diagonal to the original
* coordinate system, i.e., old_this = rot * new_this * rot^T.
* @param threshold See iteration
* @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied
* by the sum of the absolute values of the diagonal, or when maxSteps have been executed.
* @param maxSteps The iteration stops when all off-diagonal elements are less than the threshold multiplied
* by the sum of the absolute values of the diagonal, or when maxSteps have been executed.
*
* Note that this matrix is assumed to be symmetric.
*/
Expand Down Expand Up @@ -501,8 +502,8 @@ class Matrix3x3 {
/**@brief Calculate the matrix cofactor
* @param r1 The first row to use for calculating the cofactor
* @param c1 The first column to use for calculating the cofactor
* @param r1 The second row to use for calculating the cofactor
* @param c1 The second column to use for calculating the cofactor
* @param r2 The second row to use for calculating the cofactor
* @param c2 The second column to use for calculating the cofactor
* See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details
*/
TF2_PUBLIC
Expand Down
22 changes: 3 additions & 19 deletions tf2/include/tf2/LinearMath/Vector3.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3
}

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

Expand All @@ -96,8 +96,8 @@ ATTRIBUTE_ALIGNED16(class) Vector3
}


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




/**@brief Set x,y,z and zero w
* @param x Value of x
* @param y Value of y
* @param z Value of z
*/


/* void getValue(tf2Scalar *m) const
{
m[0] = m_floats[0];
m[1] = m_floats[1];
m[2] =m_floats[2];
}
*/
/**@brief Set the values
* @param x Value of x
* @param y Value of y
Expand Down
11 changes: 7 additions & 4 deletions tf2/include/tf2/buffer_core.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,12 +163,15 @@ class BufferCore : public BufferCoreInterface
const std::string & tracking_frame, const std::string & observation_frame,
const TimePoint & time, const tf2::Duration & averaging_interval) const;

/** \brief Lookup the velocity of the moving_frame in the reference_frame
* \param reference_frame The frame in which to track
* \param moving_frame The frame to track
/** \brief Lookup the velocity of the tracking_frame with respect to the observation frame in the reference_frame using the reference point.
* \param tracking_frame The frame in which to track
* \param observation_frame The frame to track
* \param reference_frame The frame in which to express the velocity
* \param reference_point The point in the reference_frame at which to compute the velocity
* \param reference_point_frame The frame in which the reference_point is expressed
* \param time The time at which to get the velocity
* \param duration The period over which to average
* \param velocity The velocity output
* \return The velocity output
*
* Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException,
* TransformReference::MaxDepthException
Expand Down
6 changes: 3 additions & 3 deletions tf2/include/tf2/convert.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,9 @@ namespace tf2
/**\brief The templated function expected to be able to do a transform
*
* This is the method which tf2 will use to try to apply a transform for any given datatype.
* \param data_in[in] The data to be transformed.
* \param data_out[inout] A reference to the output data. Note this can point to data in and the method should be mutation safe.
* \param transform[in] The transform to apply to data_in to fill data_out.
* \param[in] data_in The data to be transformed.
* \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.
* \param[in] transform The transform to apply to data_in to fill data_out.
*
* This method needs to be implemented by client library developers
*/
Expand Down