50 if (segments.size() !=
id.size())
51 segments.resize(
id.size());
52 for (
int i = 0; i < segments.size(); i++)
53 segments[i].
id =
id[i];
57 if (segments.size() != type.size())
58 segments.resize(type.size());
59 for (
int i = 0; i < segments.size(); i++)
60 segments[i].type = type[i];
64 if (segments.size() != orientation.size())
65 segments.resize(orientation.size());
66 for (
int i = 0; i < segments.size(); i++)
67 segments[i].orientation = orientation[i];
71 if (segments.size() != motion_type.size())
72 segments.resize(motion_type.size());
73 for (
int i = 0; i < segments.size(); i++)
74 segments[i].motion_type = motion_type[i];
77 const std::vector<double> &theta)
79 if (segments.size() != x.size())
80 segments.resize(x.size());
81 for (
int i = 0; i < segments.size(); i++)
83 segments[i].start.position.x = x[i];
84 segments[i].start.position.y = y[i];
85 segments[i].start.position.z = 0;
88 segments[i].start.orientation.x = q.getX();
89 segments[i].start.orientation.y = q.getY();
90 segments[i].start.orientation.z = q.getZ();
91 segments[i].start.orientation.w = q.
getW();
95 const std::vector<double> &theta)
97 if (segments.size() != x.size())
98 segments.resize(x.size());
99 for (
int i = 0; i < segments.size(); i++)
101 segments[i].end.position.x = x[i];
102 segments[i].end.position.y = y[i];
103 segments[i].end.position.z = 0;
106 segments[i].end.orientation.x = q.getX();
107 segments[i].end.orientation.y = q.getY();
108 segments[i].end.orientation.z = q.getZ();
109 segments[i].end.orientation.w = q.
getW();
113 const std::vector<double> &theta)
115 if (segments.size() != x.size())
116 segments.resize(x.size());
117 for (
int i = 0; i < segments.size(); i++)
119 segments[i].center.position.x = x[i];
120 segments[i].center.position.y = y[i];
121 segments[i].center.position.z = 0;
124 segments[i].center.orientation.x = q.getX();
125 segments[i].center.orientation.y = q.getY();
126 segments[i].center.orientation.z = q.getZ();
127 segments[i].center.orientation.w = q.
getW();
132 if (segments.size() != level.size())
133 segments.resize(level.size());
134 for (
int i = 0; i < segments.size(); i++)
135 segments[i].level = level[i];
142 std::vector<geometry_msgs::PosePtr> waypoints;
143 for (
size_t i = 0; i < segments.size(); i++)
151 path.poses.resize(waypoints.size() + 1);
155 path.poses.resize(waypoints.size());
157 for (
size_t i = 0; i < waypoints.size(); i++)
159 path.poses[i].header =
header;
160 path.poses[i].pose = *waypoints[i];
165 path.poses[waypoints.size()].header =
header;
166 path.poses[waypoints.size()].pose = segments.back().end;