@@ -52,25 +52,25 @@ namespace tf2
5252{
5353namespace impl
5454{
55- template <>
55+ template <>
5656struct defaultMessage <btVector3>
5757{
5858 using type = geometry_msgs::msg::Point;
5959};
6060
61- template <>
61+ template <>
6262struct defaultMessage <btQuaternion>
6363{
6464 using type = geometry_msgs::msg::Quaternion;
6565};
6666
67- template <>
67+ template <>
6868struct defaultMessage <btTransform>
6969{
7070 using type = geometry_msgs::msg::Transform;
7171};
7272
73- template <class Message >
73+ template <class Message >
7474struct BulletVectorImpl
7575{
7676 /* * \brief Convert a stamped Bullet Vector3 type to a PointStamped message.
@@ -98,19 +98,19 @@ struct BulletVectorImpl
9898 }
9999};
100100
101- template <>
101+ template <>
102102struct ImplDetails <btVector3, geometry_msgs::msg::Point>
103- : BulletVectorImpl<geometry_msgs::msg::Point>
103+ : BulletVectorImpl<geometry_msgs::msg::Point>
104104{
105105};
106106
107- template <>
107+ template <>
108108struct ImplDetails <btVector3, geometry_msgs::msg::Vector3>
109- : BulletVectorImpl<geometry_msgs::msg::Vector3>
109+ : BulletVectorImpl<geometry_msgs::msg::Vector3>
110110{
111111};
112112
113- template <>
113+ template <>
114114struct ImplDetails <btQuaternion, geometry_msgs::msg::Quaternion>
115115{
116116 static void toMsg (const btQuaternion & in, geometry_msgs::msg::Quaternion & msg)
@@ -127,11 +127,11 @@ struct ImplDetails<btQuaternion, geometry_msgs::msg::Quaternion>
127127 out[1 ] = msg.y ;
128128 out[2 ] = msg.z ;
129129 out[3 ] = msg.w ;
130- if (msg.w < 0 ) out *= -1 ;
130+ if (msg.w < 0 ) { out *= -1 ;}
131131 }
132132};
133133
134- template <>
134+ template <>
135135struct ImplDetails <btTransform, geometry_msgs::msg::Transform>
136136{
137137 static void fromMsg (geometry_msgs::msg::Transform const & in, btTransform & out)
@@ -168,7 +168,7 @@ inline btTransform transformToBullet(const geometry_msgs::msg::TransformStamped
168168 * \param t_out The transformed vector, as a timestamped Bullet btVector3 data type.
169169 * \param transform The timestamped transform to apply, as a TransformStamped message.
170170 */
171- template <>
171+ template <>
172172inline void doTransform (
173173 const tf2::Stamped<btVector3> & t_in, tf2::Stamped<btVector3> & t_out,
174174 const geometry_msgs::msg::TransformStamped & transform)
@@ -183,7 +183,7 @@ inline void doTransform(
183183 * \param t_out The transformed frame, as a timestamped Bullet btTransform.
184184 * \param transform The timestamped transform to apply, as a TransformStamped message.
185185 */
186- template <>
186+ template <>
187187inline void doTransform (
188188 const tf2::Stamped<btTransform> & t_in, tf2::Stamped<btTransform> & t_out,
189189 const geometry_msgs::msg::TransformStamped & transform)
0 commit comments