@@ -31,48 +31,24 @@ geometry_msgs::msg::Quaternion PoseSpline::getGeometryMsgOrientation(double time
3131}
3232
3333tf2::Vector3 PoseSpline::getPositionPos (double time) {
34- tf2::Vector3 pos;
35- pos[0 ] = x_.pos (time);
36- pos[1 ] = y_.pos (time);
37- pos[2 ] = z_.pos (time);
38- return pos;
34+ return tf2::Vector3 (x_.pos (time), y_.pos (time), z_.pos (time));
3935}
4036
4137tf2::Vector3 PoseSpline::getPositionVel (double time) {
42- tf2::Vector3 vel;
43- vel[0 ] = x_.vel (time);
44- vel[1 ] = y_.vel (time);
45- vel[2 ] = z_.vel (time);
46- return vel;
38+ return tf2::Vector3 (x_.vel (time), y_.vel (time), z_.vel (time));
4739}
4840tf2::Vector3 PoseSpline::getPositionAcc (double time) {
49- tf2::Vector3 acc;
50- acc[0 ] = x_.acc (time);
51- acc[1 ] = y_.acc (time);
52- acc[2 ] = z_.acc (time);
53- return acc;
41+ return tf2::Vector3 (x_.acc (time), y_.acc (time), z_.acc (time));
5442}
5543
5644tf2::Vector3 PoseSpline::getEulerAngles (double time) {
57- tf2::Vector3 pos;
58- pos[0 ] = roll_.pos (time);
59- pos[1 ] = pitch_.pos (time);
60- pos[2 ] = yaw_.pos (time);
61- return pos;
45+ return tf2::Vector3 (roll_.pos (time), pitch_.pos (time), yaw_.pos (time));
6246}
6347tf2::Vector3 PoseSpline::getEulerVel (double time) {
64- tf2::Vector3 vel;
65- vel[0 ] = roll_.vel (time);
66- vel[1 ] = pitch_.vel (time);
67- vel[2 ] = yaw_.vel (time);
68- return vel;
48+ return tf2::Vector3 (roll_.vel (time), pitch_.vel (time), yaw_.vel (time));
6949}
7050tf2::Vector3 PoseSpline::getEulerAcc (double time) {
71- tf2::Vector3 acc;
72- acc[0 ] = roll_.acc (time);
73- acc[1 ] = pitch_.acc (time);
74- acc[2 ] = yaw_.acc (time);
75- return acc;
51+ return tf2::Vector3 (roll_.acc (time), pitch_.acc (time), yaw_.acc (time));
7652}
7753
7854tf2::Quaternion PoseSpline::getOrientation (double time) {
0 commit comments