Skip to content

Commit bb565b9

Browse files
Reenable sensor_msgs test (#422)
* Reenable sensor_msgs cpp test Co-authored-by: Bjar Ne <[email protected]> Co-authored-by: Chris Lalancette <[email protected]>
1 parent cf61272 commit bb565b9

File tree

8 files changed

+294
-187
lines changed

8 files changed

+294
-187
lines changed

tf2_sensor_msgs/CMakeLists.txt

Lines changed: 29 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -24,24 +24,34 @@ find_package(Eigen3 REQUIRED)
2424

2525
ament_export_dependencies(eigen3_cmake_module)
2626
ament_export_dependencies(Eigen3)
27-
28-
# TODO enable tests
29-
#if(BUILD_TESTING)
30-
# catkin_add_nosetests(test/test_tf2_sensor_msgs.py)
31-
32-
#find_package(catkin REQUIRED COMPONENTS
33-
# sensor_msgs
34-
# rostest
35-
# tf2_ros
36-
# tf2
37-
#)
38-
#include_directories(${EIGEN_INCLUDE_DIRS})
39-
#add_executable(test_tf2_sensor_msgs_cpp EXCLUDE_FROM_ALL test/test_tf2_sensor_msgs.cpp)
40-
#target_link_libraries(test_tf2_sensor_msgs_cpp ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
41-
#if(TARGET tests)
42-
# add_dependencies(tests test_tf2_sensor_msgs_cpp)
43-
#endif()
44-
#add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test.launch)
45-
#endif()
27+
ament_export_dependencies(tf2)
28+
ament_export_dependencies(tf2_ros)
29+
30+
if(BUILD_TESTING)
31+
find_package(ament_cmake_gtest REQUIRED)
32+
find_package(ament_lint_auto REQUIRED)
33+
34+
# TODO(ros2/geometry2#259) Remove once headers
35+
# are renamed to .hpp
36+
set(ament_cmake_uncrustify_ADDITIONAL_ARGS --language CPP)
37+
set(ament_cmake_cppcheck_LANGUAGE c++)
38+
ament_lint_auto_find_test_dependencies()
39+
40+
# TODO(ros2/orocos_kinematics_dynamics): reenable when PyKDL is ready to use
41+
#find_package(ament_cmake_pytest REQUIRED)
42+
#ament_add_pytest_test(test_tf2_sensor_msgs_py test/test_tf2_sensor_msgs.py)
43+
44+
ament_add_gtest(test_tf2_sensor_msgs_cpp test/test_tf2_sensor_msgs.cpp)
45+
if(TARGET test_tf2_sensor_msgs_cpp)
46+
target_include_directories(test_tf2_sensor_msgs_cpp PUBLIC include)
47+
ament_target_dependencies(test_tf2_sensor_msgs_cpp
48+
"Eigen3"
49+
"rclcpp"
50+
"sensor_msgs"
51+
"tf2"
52+
"tf2_ros"
53+
)
54+
endif()
55+
endif()
4656

4757
ament_auto_package()
Lines changed: 30 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -1,37 +1,36 @@
1-
/*
2-
* Copyright (c) 2008, Willow Garage, Inc.
3-
* All rights reserved.
4-
*
5-
* Redistribution and use in source and binary forms, with or without
6-
* modification, are permitted provided that the following conditions are met:
7-
*
8-
* * Redistributions of source code must retain the above copyright
9-
* notice, this list of conditions and the following disclaimer.
10-
* * Redistributions in binary form must reproduce the above copyright
11-
* notice, this list of conditions and the following disclaimer in the
12-
* documentation and/or other materials provided with the distribution.
13-
* * Neither the name of the Willow Garage, Inc. nor the names of its
14-
* contributors may be used to endorse or promote products derived from
15-
* this software without specific prior written permission.
16-
*
17-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18-
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19-
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20-
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21-
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22-
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23-
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24-
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25-
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26-
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27-
* POSSIBILITY OF SUCH DAMAGE.
28-
*/
1+
// Copyright 2008 Willow Garage, Inc.
2+
//
3+
// Redistribution and use in source and binary forms, with or without
4+
// modification, are permitted provided that the following conditions are met:
5+
//
6+
// * Redistributions of source code must retain the above copyright
7+
// notice, this list of conditions and the following disclaimer.
8+
//
9+
// * Redistributions in binary form must reproduce the above copyright
10+
// notice, this list of conditions and the following disclaimer in the
11+
// documentation and/or other materials provided with the distribution.
12+
//
13+
// * Neither the name of the Willow Garage, Inc. nor the names of its
14+
// contributors may be used to endorse or promote products derived from
15+
// this software without specific prior written permission.
16+
//
17+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
// POSSIBILITY OF SUCH DAMAGE.
2928

30-
#ifndef TF2_SENSOR_MSGS_H
31-
#define TF2_SENSOR_MSGS_H
29+
#ifndef TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_H_
30+
#define TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_H_
3231

3332
#warning This header is obsolete, please include tf2_sensor_msgs/tf2_sensor_msgs.hpp instead
3433

3534
#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
3635

37-
#endif // TF2_SENSOR_MSGS_H
36+
#endif // TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_H_
Lines changed: 62 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -1,34 +1,33 @@
1-
/*
2-
* Copyright (c) 2008, Willow Garage, Inc.
3-
* All rights reserved.
4-
*
5-
* Redistribution and use in source and binary forms, with or without
6-
* modification, are permitted provided that the following conditions are met:
7-
*
8-
* * Redistributions of source code must retain the above copyright
9-
* notice, this list of conditions and the following disclaimer.
10-
* * Redistributions in binary form must reproduce the above copyright
11-
* notice, this list of conditions and the following disclaimer in the
12-
* documentation and/or other materials provided with the distribution.
13-
* * Neither the name of the Willow Garage, Inc. nor the names of its
14-
* contributors may be used to endorse or promote products derived from
15-
* this software without specific prior written permission.
16-
*
17-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18-
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19-
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20-
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21-
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22-
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23-
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24-
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25-
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26-
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27-
* POSSIBILITY OF SUCH DAMAGE.
28-
*/
1+
// Copyright 2008 Willow Garage, Inc.
2+
//
3+
// Redistribution and use in source and binary forms, with or without
4+
// modification, are permitted provided that the following conditions are met:
5+
//
6+
// * Redistributions of source code must retain the above copyright
7+
// notice, this list of conditions and the following disclaimer.
8+
//
9+
// * Redistributions in binary form must reproduce the above copyright
10+
// notice, this list of conditions and the following disclaimer in the
11+
// documentation and/or other materials provided with the distribution.
12+
//
13+
// * Neither the name of the Willow Garage, Inc. nor the names of its
14+
// contributors may be used to endorse or promote products derived from
15+
// this software without specific prior written permission.
16+
//
17+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
// POSSIBILITY OF SUCH DAMAGE.
2928

30-
#ifndef TF2_SENSOR_MSGS_HPP
31-
#define TF2_SENSOR_MSGS_HPP
29+
#ifndef TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_HPP_
30+
#define TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_HPP_
3231

3332
#include <tf2/convert.h>
3433
#include <tf2/time.h>
@@ -38,6 +37,8 @@
3837
#include <Eigen/Geometry>
3938
#include <tf2_ros/buffer_interface.h>
4039

40+
#include <string>
41+
4142
namespace tf2
4243
{
4344

@@ -46,26 +47,42 @@ namespace tf2
4647
/********************/
4748

4849
// method to extract timestamp from object
49-
template <>
50+
template<>
5051
inline
51-
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2& p) {return tf2_ros::fromMsg(p.header.stamp);}
52+
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2 & p)
53+
{
54+
return tf2_ros::fromMsg(p.header.stamp);
55+
}
5256

5357
// method to extract frame id from object
54-
template <>
58+
template<>
5559
inline
56-
std::string getFrameId(const sensor_msgs::msg::PointCloud2 &p) {return p.header.frame_id;}
60+
std::string getFrameId(const sensor_msgs::msg::PointCloud2 & p) {return p.header.frame_id;}
5761

5862
// this method needs to be implemented by client library developers
59-
template <>
63+
template<>
6064
inline
61-
void doTransform(const sensor_msgs::msg::PointCloud2 &p_in, sensor_msgs::msg::PointCloud2 &p_out, const geometry_msgs::msg::TransformStamped& t_in)
65+
void doTransform(
66+
const sensor_msgs::msg::PointCloud2 & p_in, sensor_msgs::msg::PointCloud2 & p_out,
67+
const geometry_msgs::msg::TransformStamped & t_in)
6268
{
6369
p_out = p_in;
6470
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);
71+
// FIXME(clalancette): The static casts to float aren't ideal; the incoming
72+
// transform uses double, and hence may have values that are too large to represent
73+
// in a float. But since this method implicitly returns a float PointCloud2, we don't
74+
// have much choice here without subtly changing the API.
75+
auto translation = Eigen::Translation3f(
76+
static_cast<float>(t_in.transform.translation.x),
77+
static_cast<float>(t_in.transform.translation.y),
78+
static_cast<float>(t_in.transform.translation.z));
79+
auto quaternion = Eigen::Quaternion<float>(
80+
static_cast<float>(t_in.transform.rotation.w),
81+
static_cast<float>(t_in.transform.rotation.x),
82+
static_cast<float>(t_in.transform.rotation.y),
83+
static_cast<float>(t_in.transform.rotation.z));
84+
85+
Eigen::Transform<float, 3, Eigen::Affine> t = translation * quaternion;
6986

7087
sensor_msgs::PointCloud2ConstIterator<float> x_in(p_in, std::string("x"));
7188
sensor_msgs::PointCloud2ConstIterator<float> y_in(p_in, std::string("y"));
@@ -76,24 +93,24 @@ void doTransform(const sensor_msgs::msg::PointCloud2 &p_in, sensor_msgs::msg::Po
7693
sensor_msgs::PointCloud2Iterator<float> z_out(p_out, std::string("z"));
7794

7895
Eigen::Vector3f point;
79-
for(; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
96+
for (; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
8097
point = t * Eigen::Vector3f(*x_in, *y_in, *z_in);
8198
*x_out = point.x();
8299
*y_out = point.y();
83100
*z_out = point.z();
84101
}
85102
}
86103
inline
87-
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 &in)
104+
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 & in)
88105
{
89106
return in;
90107
}
91108
inline
92-
void fromMsg(const sensor_msgs::msg::PointCloud2 &msg, sensor_msgs::msg::PointCloud2 &out)
109+
void fromMsg(const sensor_msgs::msg::PointCloud2 & msg, sensor_msgs::msg::PointCloud2 & out)
93110
{
94111
out = msg;
95112
}
96113

97-
} // namespace
114+
} // namespace tf2
98115

99-
#endif // TF2_SENSOR_MSGS_HPP
116+
#endif // TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_HPP_

tf2_sensor_msgs/package.xml

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,12 +23,13 @@
2323
<depend>sensor_msgs</depend>
2424
<depend>tf2</depend>
2525
<depend>tf2_ros</depend>
26-
<!-- <depend>python_orocos_kdl</depend> -->
27-
<!-- <test_depend>rostest</test_depend> -->
2826

2927
<exec_depend>tf2_ros_py</exec_depend>
3028

3129
<test_depend>ament_cmake_gtest</test_depend>
30+
<test_depend>ament_lint_auto</test_depend>
31+
<test_depend>ament_lint_common</test_depend>
32+
<test_depend>rclcpp</test_depend>
3233

3334
<export>
3435
<build_type>ament_cmake</build_type>
Lines changed: 29 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1,29 @@
1-
from tf2_sensor_msgs import *
1+
# Copyright 2008 Willow Garage, Inc.
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the Willow Garage, Inc. nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
29+
from tf2_sensor_msgs import * # noqa(E401)

0 commit comments

Comments
 (0)