Skip to content

Commit 171cfe0

Browse files
committed
tf2_bullet doxygen
1 parent 3163ab2 commit 171cfe0

File tree

1 file changed

+25
-1
lines changed

1 file changed

+25
-1
lines changed

tf2_bullet/include/tf2_bullet/tf2_bullet.h

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,43 +52,57 @@ namespace tf2
5252
{
5353
namespace impl
5454
{
55+
/// \brief Default return type of tf2::toMsg() for btVector3.
5556
template<>
5657
struct defaultMessage<btVector3>
5758
{
59+
/// \brief Default return type of tf2::toMsg() for btVector3.
5860
using type = geometry_msgs::msg::Point;
5961
};
6062

63+
/// \brief Default return type of tf2::toMsg() for btQuaternion.
6164
template<>
6265
struct defaultMessage<btQuaternion>
6366
{
67+
/// \brief Default return type of tf2::toMsg() for btQuaternion.
6468
using type = geometry_msgs::msg::Quaternion;
6569
};
6670

71+
/// \brief Default return type of tf2::toMsg() for btTransform.
6772
template<>
6873
struct defaultMessage<btTransform>
6974
{
75+
/// \brief Default return type of tf2::toMsg() for btTransform.
7076
using type = geometry_msgs::msg::Transform;
7177
};
7278

79+
/// \brief Conversion implementation for geometry_msgs::msg::Point and btVector3.
7380
template<>
7481
struct ImplDetails<btVector3, geometry_msgs::msg::Point>
7582
: DefaultVectorImpl<btVector3, geometry_msgs::msg::Point>
7683
{
7784
};
7885

86+
/// \brief Conversion implementation for geometry_msgs::msg::Vector3 and btVector3.
7987
template<>
8088
struct ImplDetails<btVector3, geometry_msgs::msg::Vector3>
8189
: DefaultVectorImpl<btVector3, geometry_msgs::msg::Vector3>
8290
{
8391
};
8492

93+
/// \brief Conversion implementation for geometry_msgs::msg::Quaternion and Eigen::Quaterniond.
8594
template<>
8695
struct ImplDetails<btQuaternion, geometry_msgs::msg::Quaternion>
8796
: DefaultQuaternionImpl<btQuaternion> {};
8897

98+
/// \brief Conversion implementation for geometry_msgs::msg::Transform and btTransform.
8999
template<>
90100
struct ImplDetails<btTransform, geometry_msgs::msg::Transform>
91101
{
102+
/** \brief Convert a Transform message to a btTransform type.
103+
* \param[in] in The message to convert.
104+
* \param[out] out The converted message, as a btTransform type.
105+
*/
92106
static void fromMsg(geometry_msgs::msg::Transform const & in, btTransform & out)
93107
{
94108
btVector3 trans;
@@ -98,34 +112,44 @@ struct ImplDetails<btTransform, geometry_msgs::msg::Transform>
98112
out = btTransform(rot, trans);
99113
}
100114

115+
/** \brief Convert a btTransform to a Transform message.
116+
* \param[in] in The btTransform to convert.
117+
* \param[out] out The converted Transform, as a message.
118+
*/
101119
static void toMsg(btTransform const & in, geometry_msgs::msg::Transform & out)
102120
{
103121
tf2::toMsg<>(in.getRotation(), out.rotation);
104122
tf2::toMsg<>(in.getOrigin(), out.translation);
105123
}
106124
};
107125

126+
/// \brief Default Type for automatic tf2::doTransform() implementation for btTransform.
108127
template<>
109128
struct DefaultTransformType<btTransform>
110129
{
130+
/// \brief Default Type for automatic tf2::doTransform() implementation for btTransform.
111131
using type = btTransform;
112132
};
113133

134+
/// \brief Default Type for automatic tf2::doTransform() implementation for btVector3.
114135
template<>
115136
struct DefaultTransformType<btVector3>
116137
{
138+
/// \brief Default Type for automatic tf2::doTransform() implementation for btVector3.
117139
using type = btTransform;
118140
};
119141

142+
/// \brief Default Type for automatic tf2::doTransform() implementation for btQuaternion.
120143
template<>
121144
struct DefaultTransformType<btQuaternion>
122145
{
146+
/// \brief Default Type for automatic tf2::doTransform() implementation for btTransform.
123147
using type = btTransform;
124148
};
125149
} // namespace impl
126150

127151
/** \brief Convert a timestamped transform to the equivalent Bullet data type.
128-
* \param t The transform to convert, as a geometry_msgs TransformedStamped message.
152+
* \param[in] t The transform to convert, as a geometry_msgs TransformedStamped message.
129153
* \return The transform message converted to a Bullet btTransform.
130154
*/
131155
inline btTransform transformToBullet(const geometry_msgs::msg::TransformStamped & t)

0 commit comments

Comments
 (0)