conversions_deprecated.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11 
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 #ifndef MAV_PLANNING_MSGS_CONVERSIONS_DEPRECATED_H
20 #define MAV_PLANNING_MSGS_CONVERSIONS_DEPRECATED_H
21 
22 #include <geometry_msgs/Point.h>
23 #include <geometry_msgs/Quaternion.h>
24 #include <geometry_msgs/Vector3.h>
25 
26 #include "mav_planning_msgs/PolynomialSegment4D.h"
27 #include "mav_planning_msgs/PolynomialTrajectory4D.h"
29 
30 namespace mav_planning_msgs {
31 
33 inline void vectorFromMsgArray(const PolynomialSegment4D::_x_type& array,
34  Eigen::VectorXd* x);
35 
37 inline void msgArrayFromVector(const Eigen::VectorXd& x,
38  PolynomialSegment4D::_x_type* array);
39 
41 inline void eigenPolynomialSegmentFromMsg(const PolynomialSegment4D& msg,
42  EigenPolynomialSegment* segment) {
43  assert(segment != NULL);
44 
45  vectorFromMsgArray(msg.x, &(segment->x));
46  vectorFromMsgArray(msg.y, &(segment->y));
47  vectorFromMsgArray(msg.z, &(segment->z));
48  vectorFromMsgArray(msg.yaw, &(segment->yaw));
49 
50  segment->segment_time_ns = msg.segment_time.toNSec();
51  segment->num_coeffs = msg.num_coeffs;
52 }
53 
56  const PolynomialTrajectory4D& msg,
57  EigenPolynomialTrajectory* eigen_trajectory) {
58  assert(eigen_trajectory != NULL);
59  eigen_trajectory->clear();
60  eigen_trajectory->reserve(msg.segments.size());
61  for (PolynomialTrajectory4D::_segments_type::const_iterator it =
62  msg.segments.begin();
63  it != msg.segments.end(); ++it) {
64  EigenPolynomialSegment segment;
65  eigenPolynomialSegmentFromMsg(*it, &segment);
66  eigen_trajectory->push_back(segment);
67  }
68 }
69 
70 
74  PolynomialSegment4D* msg) {
75  assert(msg != NULL);
76  msgArrayFromVector(segment.x, &(msg->x));
77  msgArrayFromVector(segment.y, &(msg->y));
78  msgArrayFromVector(segment.z, &(msg->z));
79  msgArrayFromVector(segment.yaw, &(msg->yaw));
80 
81  msg->segment_time.fromNSec(segment.segment_time_ns);
82  msg->num_coeffs = segment.num_coeffs;
83 }
84 
88  const EigenPolynomialTrajectory& eigen_trajectory,
89  PolynomialTrajectory4D* msg) {
90  assert(msg != NULL);
91  msg->segments.reserve(eigen_trajectory.size());
92  for (EigenPolynomialTrajectory::const_iterator it = eigen_trajectory.begin();
93  it != eigen_trajectory.end(); ++it) {
94  PolynomialSegment4D segment;
95  polynomialSegmentMsgFromEigen(*it, &segment);
96  msg->segments.push_back(segment);
97  }
98 }
99 
100 } // namespace mav_planning_msgs
101 
102 #endif // MAV_PLANNING_MSGS_CONVERSIONS_DEPRECATED_H
void polynomialTrajectoryMsgFromEigen(const EigenPolynomialTrajectory &eigen_trajectory, PolynomialTrajectory *msg)
Definition: conversions.h:102
void vectorFromMsgArray(const PolynomialSegment::_x_type &array, Eigen::VectorXd *x)
Converts a PolynomialSegment double array to an Eigen::VectorXd.
Definition: conversions.h:36
void eigenPolynomialSegmentFromMsg(const PolynomialSegment &msg, EigenPolynomialSegment *segment)
Converts a PolynomialSegment message to an EigenPolynomialSegment structure.
Definition: conversions.h:51
void eigenPolynomialTrajectoryFromMsg(const PolynomialTrajectory &msg, EigenPolynomialTrajectory *eigen_trajectory)
Converts a PolynomialTrajectory message to a EigenPolynomialTrajectory.
Definition: conversions.h:68
std::vector< EigenPolynomialSegment > EigenPolynomialTrajectory
void polynomialSegmentMsgFromEigen(const EigenPolynomialSegment &segment, PolynomialSegment *msg)
Definition: conversions.h:85
void msgArrayFromVector(const Eigen::VectorXd &x, PolynomialSegment::_x_type *array)
Converts an Eigen::VectorXd to a PolynomialSegment double array.
Definition: conversions.h:42


mav_planning_msgs
Author(s): Simon Lynen, Markus Achtelik, Pascal Gohl, Sammy Omari, Michael Burri, Fadri Furrer, Helen Oleynikova, Karen Bodie, Rik Bähnemann
autogenerated on Thu Jan 23 2020 03:14:00