Skip to content

Commit 3278ca2

Browse files
committed
Add static_cast to tf2_bullet
bullet uses floats, which causes narrowing warnings
1 parent a336830 commit 3278ca2

File tree

2 files changed

+15
-7
lines changed

2 files changed

+15
-7
lines changed

tf2/include/tf2/impl/convert.h

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -508,8 +508,9 @@ struct StampedAttributesHelper<tf2::WithCovarianceStamped<T>>
508508
*
509509
* \tparam VectorType Datatype of the Vector.
510510
* \tparam Message Message type, like geometry_msgs::msg::Vector3.
511+
* \tparam VectorMemberType Type of the <tt>x, y</tt> and \c z variables of the vector
511512
*/
512-
template<class VectorType, class Message>
513+
template<class VectorType, class Message, typename VectorMemberType = double>
513514
struct DefaultVectorConversionImplementation
514515
{
515516
/** \brief Convert a vector type to a vector-like message.
@@ -529,16 +530,20 @@ struct DefaultVectorConversionImplementation
529530
*/
530531
static void fromMsg(const Message & msg, VectorType & out)
531532
{
532-
out = VectorType(msg.x, msg.y, msg.z);
533+
// cast to suppress narrowing warning
534+
out = VectorType(
535+
static_cast<VectorMemberType>(msg.x), static_cast<VectorMemberType>(msg.y),
536+
static_cast<VectorMemberType>(msg.z));
533537
}
534538
};
535539

536540
/** \brief Generic conversion of a quaternion and
537541
* a geometry_msgs::msg::Quaternion message.
538542
*
539543
* \tparam QuaternionType Datatype of the Vector.
544+
* \tparam QuaternionMemberType Type of the <tt>x, y, z</tt> and \c w variables of the quaternion
540545
*/
541-
template<class QuaternionType>
546+
template<class QuaternionType, typename QuaternionMemberType = double>
542547
struct DefaultQuaternionConversionImplementation
543548
{
544549
/** \brief Convert a quaternion type to a Quaternion message.
@@ -559,7 +564,10 @@ struct DefaultQuaternionConversionImplementation
559564
*/
560565
static void fromMsg(const geometry_msgs::msg::Quaternion & msg, QuaternionType & out)
561566
{
562-
out = QuaternionType(msg.x, msg.y, msg.z, msg.w);
567+
// cast to suppress narrowing warning
568+
out = QuaternionType(
569+
static_cast<QuaternionMemberType>(msg.x), static_cast<QuaternionMemberType>(msg.y),
570+
static_cast<QuaternionMemberType>(msg.z), static_cast<QuaternionMemberType>(msg.w));
563571
}
564572
};
565573

tf2_bullet/include/tf2_bullet/tf2_bullet.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -79,21 +79,21 @@ struct DefaultMessageForDatatype<btTransform>
7979
/// \brief Conversion implementation for geometry_msgs::msg::Point and btVector3.
8080
template<>
8181
struct ConversionImplementation<btVector3, geometry_msgs::msg::Point>
82-
: DefaultVectorConversionImplementation<btVector3, geometry_msgs::msg::Point>
82+
: DefaultVectorConversionImplementation<btVector3, geometry_msgs::msg::Point, btScalar>
8383
{
8484
};
8585

8686
/// \brief Conversion implementation for geometry_msgs::msg::Vector3 and btVector3.
8787
template<>
8888
struct ConversionImplementation<btVector3, geometry_msgs::msg::Vector3>
89-
: DefaultVectorConversionImplementation<btVector3, geometry_msgs::msg::Vector3>
89+
: DefaultVectorConversionImplementation<btVector3, geometry_msgs::msg::Vector3, btScalar>
9090
{
9191
};
9292

9393
/// \brief Conversion implementation for geometry_msgs::msg::Quaternion and Eigen::Quaterniond.
9494
template<>
9595
struct ConversionImplementation<btQuaternion, geometry_msgs::msg::Quaternion>
96-
: DefaultQuaternionConversionImplementation<btQuaternion> {};
96+
: DefaultQuaternionConversionImplementation<btQuaternion, btScalar> {};
9797

9898
/// \brief Conversion implementation for geometry_msgs::msg::Transform and btTransform.
9999
template<>

0 commit comments

Comments
 (0)