Skip to content

Commit 283cc4b

Browse files
committed
Add static_casts for Windows compile warning.
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 7eb81ba commit 283cc4b

File tree

1 file changed

+15
-4
lines changed

1 file changed

+15
-4
lines changed

tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.hpp

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -62,10 +62,21 @@ void doTransform(const sensor_msgs::msg::PointCloud2 &p_in, sensor_msgs::msg::Po
6262
{
6363
p_out = p_in;
6464
p_out.header = t_in.header;
65-
Eigen::Transform<float,3,Eigen::Affine> t = Eigen::Translation3f(t_in.transform.translation.x, t_in.transform.translation.y,
66-
t_in.transform.translation.z) * Eigen::Quaternion<float>(
67-
t_in.transform.rotation.w, t_in.transform.rotation.x,
68-
t_in.transform.rotation.y, t_in.transform.rotation.z);
65+
// FIXME(clalancette): The static casts to float aren't ideal; the incoming
66+
// transform uses double, and hence may have values that are too large to represent
67+
// in a float. But since this method implicitly returns a float PointCloud2, we don't
68+
// have much choice here without subtly changing the API.
69+
auto translation = Eigen::Translation3f(
70+
static_cast<float>(t_in.transform.translation.x),
71+
static_cast<float>(t_in.transform.translation.y),
72+
static_cast<float>(t_in.transform.translation.z));
73+
auto quaternion = Eigen::Quaternion<float>(
74+
static_cast<float>(t_in.transform.rotation.w),
75+
static_cast<float>(t_in.transform.rotation.x),
76+
static_cast<float>(t_in.transform.rotation.y),
77+
static_cast<float>(t_in.transform.rotation.z));
78+
79+
Eigen::Transform<float,3,Eigen::Affine> t = translation * quaternion;
6980

7081
sensor_msgs::PointCloud2ConstIterator<float> x_in(p_in, std::string("x"));
7182
sensor_msgs::PointCloud2ConstIterator<float> y_in(p_in, std::string("y"));

0 commit comments

Comments
 (0)