13
13
// limitations under the License.
14
14
15
15
#include " autoware/object_recognition_utils/predicted_path_utils.hpp"
16
- #include " autoware/universe_utils /geometry/geometry.hpp"
17
- #include " autoware/universe_utils /math/unit_conversion.hpp"
16
+ #include " autoware_utils /geometry/geometry.hpp"
17
+ #include " autoware_utils /math/unit_conversion.hpp"
18
18
19
19
#include < boost/optional/optional_io.hpp>
20
20
21
21
#include < gtest/gtest.h>
22
22
23
23
#include < vector>
24
24
25
- using autoware::universe_utils ::Point2d;
26
- using autoware::universe_utils ::Point3d;
25
+ using autoware_utils ::Point2d;
26
+ using autoware_utils ::Point3d;
27
27
28
28
constexpr double epsilon = 1e-06 ;
29
29
30
30
namespace
31
31
{
32
- using autoware::universe_utils::createPoint ;
33
- using autoware::universe_utils::createQuaternionFromRPY ;
34
- using autoware::universe_utils::transformPoint ;
32
+ using autoware_utils::create_point ;
33
+ using autoware_utils::create_quaternion_from_rpy ;
34
+ using autoware_utils::transform_point ;
35
35
using autoware_perception_msgs::msg::PredictedPath;
36
36
37
37
geometry_msgs::msg::Pose createPose (
38
38
double x, double y, double z, double roll, double pitch, double yaw)
39
39
{
40
40
geometry_msgs::msg::Pose p;
41
- p.position = createPoint (x, y, z);
42
- p.orientation = createQuaternionFromRPY (roll, pitch, yaw);
41
+ p.position = create_point (x, y, z);
42
+ p.orientation = create_quaternion_from_rpy (roll, pitch, yaw);
43
43
return p;
44
44
}
45
45
@@ -67,15 +67,15 @@ PredictedPath createTestPredictedPath(
67
67
TEST (predicted_path_utils, testCalcInterpolatedPose)
68
68
{
69
69
using autoware::object_recognition_utils::calcInterpolatedPose;
70
- using autoware::universe_utils::createQuaternionFromRPY ;
71
- using autoware::universe_utils::createQuaternionFromYaw ;
72
- using autoware::universe_utils ::deg2rad;
70
+ using autoware_utils::create_quaternion_from_rpy ;
71
+ using autoware_utils::create_quaternion_from_yaw ;
72
+ using autoware_utils ::deg2rad;
73
73
74
74
const auto path = createTestPredictedPath (100 , 0.1 , 1.0 );
75
75
76
76
// Normal Case (same point as the original point)
77
77
{
78
- const auto ans_quat = createQuaternionFromRPY (deg2rad (0.0 ), deg2rad (0.0 ), deg2rad (0.0 ));
78
+ const auto ans_quat = create_quaternion_from_rpy (deg2rad (0.0 ), deg2rad (0.0 ), deg2rad (0.0 ));
79
79
for (double t = 0.0 ; t < 9.0 + 1e-6 ; t += 1.0 ) {
80
80
const auto p = calcInterpolatedPose (path, t);
81
81
@@ -92,7 +92,7 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
92
92
93
93
// Normal Case (random case)
94
94
{
95
- const auto ans_quat = createQuaternionFromRPY (deg2rad (0.0 ), deg2rad (0.0 ), deg2rad (0.0 ));
95
+ const auto ans_quat = create_quaternion_from_rpy (deg2rad (0.0 ), deg2rad (0.0 ), deg2rad (0.0 ));
96
96
for (double t = 0.0 ; t < 9.0 ; t += 0.3 ) {
97
97
const auto p = calcInterpolatedPose (path, t);
98
98
@@ -133,9 +133,9 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
133
133
TEST (predicted_path_utils, resamplePredictedPath_by_vector)
134
134
{
135
135
using autoware::object_recognition_utils::resamplePredictedPath;
136
- using autoware::universe_utils::createQuaternionFromRPY ;
137
- using autoware::universe_utils::createQuaternionFromYaw ;
138
- using autoware::universe_utils ::deg2rad;
136
+ using autoware_utils::create_quaternion_from_rpy ;
137
+ using autoware_utils::create_quaternion_from_yaw ;
138
+ using autoware_utils ::deg2rad;
139
139
140
140
const auto path = createTestPredictedPath (10 , 1.0 , 1.0 );
141
141
@@ -210,9 +210,9 @@ TEST(predicted_path_utils, resamplePredictedPath_by_vector)
210
210
TEST (predicted_path_utils, resamplePredictedPath_by_sampling_time)
211
211
{
212
212
using autoware::object_recognition_utils::resamplePredictedPath;
213
- using autoware::universe_utils::createQuaternionFromRPY ;
214
- using autoware::universe_utils::createQuaternionFromYaw ;
215
- using autoware::universe_utils ::deg2rad;
213
+ using autoware_utils::create_quaternion_from_rpy ;
214
+ using autoware_utils::create_quaternion_from_yaw ;
215
+ using autoware_utils ::deg2rad;
216
216
217
217
const auto path = createTestPredictedPath (10 , 1.0 , 1.0 );
218
218
0 commit comments