Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include <cob_trajectory_controller/RefValJS_PTP_Trajectory.h>
00019 #include <stdexcept>
00020 #include <algorithm>
00021 #include <vector>
00022
00023
00024
00025 const double RefValJS_PTP_Trajectory::weigths[] = { 1.5, 1.5, 1.0, 1.0, 0.8, 0.8, 0.7 };
00026
00027
00028 inline double sqr(double x)
00029 {
00030 return x*x;
00031 }
00032
00033 RefValJS_PTP_Trajectory::RefValJS_PTP_Trajectory(const trajectory_msgs::JointTrajectory& trajectory, double v_rad_s, double a_rad_s2, bool smooth)
00034 {
00035 m_trajectory = trajectory;
00036 m_length = 0;
00037
00038 m_stepSize = 0.0175;
00039 m_length_parts.clear();
00040 m_s_parts.clear();
00041
00042 if ( m_trajectory.points.size() < 1 )
00043 {
00044 throw std::runtime_error("Tried to create reference values for empty trajectory!");
00045 }
00046
00047 std::vector<std::vector<double> > zwischenPunkte;
00048
00049 if (smooth == false)
00050 {
00051
00052
00053
00054
00055 double between_stepsize = 0.8;
00056 for (unsigned int i=0; i < m_trajectory.points.size()-1; i++)
00057 {
00058 std::vector<double> direction;
00059 direction.resize( m_trajectory.points[i+1].positions.size());
00060 double len = 0;
00061 for(unsigned int j = 0; j < m_trajectory.points[i+1].positions.size(); j++)
00062 {
00063 direction.at(j) = m_trajectory.points[i+1].positions.at(j)-m_trajectory.points[i].positions.at(j);
00064 len += direction.at(j) * direction.at(j);
00065 }
00066 double dist = sqrt(len);
00067 int num_segs = ceil(dist/between_stepsize);
00068 zwischenPunkte.resize(num_segs);
00069 for (int j=0; j < num_segs; j++)
00070 {
00071 std::vector<double> betw_joint;
00072 betw_joint.resize(direction.size());
00073 for(unsigned int d=0; d < direction.size(); d++)
00074 {
00075 betw_joint.at(d) = m_trajectory.points[i].positions.at(d) + direction.at(d) * ( (double)j / (double)num_segs );
00076 }
00077 zwischenPunkte.at(j) = betw_joint;
00078 }
00079 }
00080 zwischenPunkte.push_back( m_trajectory.points.back().positions );
00081 } else
00082 {
00083 zwischenPunkte.resize(trajectory.points.size());
00084 for(unsigned int i = 0; i < trajectory.points.size(); i++)
00085 {
00086 zwischenPunkte.at(i) = trajectory.points.at(i).positions;
00087 }
00088 }
00089 ROS_INFO("Calculated %lu zwischenPunkte", zwischenPunkte.size());
00090
00091 m_TrajectorySpline.setCtrlPoints(zwischenPunkte);
00092
00093
00094
00095 if ( m_TrajectorySpline.ipoWithConstSampleDist(m_stepSize, m_SplinePoints)==false )
00096 {
00097
00098
00099 throw std::runtime_error("Error in BSplineND::ipoWithConstSampleDist!");
00100 }
00101 m_SplinePoints = zwischenPunkte;
00102 ROS_INFO("Calculated %lu splinepoints", m_SplinePoints.size());
00103
00104 m_length_cumulated.clear();
00105 m_length_cumulated.push_back(0.0);
00106
00107 for (unsigned int i=0; i < m_SplinePoints.size()-1; i++)
00108 {
00109 std::vector<double> dist;
00110 dist.resize(m_SplinePoints[i].size());
00111 for(unsigned int j=0; j < m_SplinePoints[i].size(); j++)
00112 {
00113 dist.at(j) = m_SplinePoints[i+1].at(j) - m_SplinePoints[i].at(j);
00114 }
00115
00116
00117 m_length_parts.push_back( norm(dist) );
00118 m_length += norm(dist);
00119 m_length_cumulated.push_back(m_length);
00120 }
00121
00122 m_param_length = m_TrajectorySpline.getMaxdPos();
00123
00124 for (unsigned int i=0; i < m_length_parts.size(); i++)
00125 {
00126 m_s_parts.push_back( m_length_parts[i] / m_length );
00127 }
00128
00129 m_v_rad_s = v_rad_s;
00130 m_a_rad_s2 = a_rad_s2;
00131
00132
00133 double a = fabs(m_a_rad_s2);
00134 double v = fabs(m_v_rad_s);
00135
00136 if (m_length > v*v/a)
00137 {
00138
00139 m_T1 = m_T3 = v / a;
00140 m_T2 = (m_length - v*v/a) / v;
00141
00142
00143 m_sv2 = 1.0 / (m_T1 + m_T2);
00144 m_sa1 = m_sv2 / m_T1;
00145 m_sa3 = -m_sa1;
00146 }
00147 else {
00148
00149 m_T2 = 0.0;
00150 m_T1 = m_T3 = sqrt(m_length / a);
00151
00152 m_sv2 = 1.0 / m_T1;
00153 m_sa1 = m_sv2 / m_T1;
00154 m_sa3 = -m_sa1;
00155
00156 }
00157
00158
00159 }
00160
00161 std::vector<double> RefValJS_PTP_Trajectory::r(double s) const
00162 {
00163
00164 std::vector<double> soll;
00165 if (s <= 0)
00166 {
00167 soll = m_trajectory.points.front().positions;
00168 } else
00169 if (s < 1)
00170 {
00171
00172
00173
00174
00175
00176
00177
00178
00179 vecd_it start = m_length_cumulated.begin();
00180 vecd_it end = m_length_cumulated.end();
00181 vecd_it it = upper_bound(start, end, s * m_length);
00182
00183 int i = int(it-start) - 1;
00184 double frac = (s * m_length - m_length_cumulated[i]) / m_length_parts[i];
00185
00186
00187
00188
00189
00190
00191
00192 soll.resize(m_SplinePoints[i].size());
00193 for(unsigned int j = 0; j < m_SplinePoints[i].size(); j++)
00194 {
00195 soll.at(j) = m_SplinePoints[i].at(j) + (m_SplinePoints[i+1].at(j)-m_SplinePoints[i].at(j))*frac;
00196 }
00197 }
00198 else
00199 {
00200 soll = m_trajectory.points.back().positions;
00201 }
00202 return soll;
00203 }
00204
00205 double RefValJS_PTP_Trajectory::s(double t) const
00206 {
00207 if (t >= m_T1 + m_T2 + m_T3)
00208 return 1.0;
00209 else if (t >= m_T1 + m_T2)
00210 {
00211 return 0.5*m_sa1*m_T1*m_T1 + m_sv2*m_T2 + m_sv2*(t-m_T1-m_T2) + 0.5*m_sa3*sqr(t-m_T1-m_T2);
00212 }
00213 else if (t >= m_T1)
00214 {
00215 return 0.5*m_sa1*m_T1*m_T1 + m_sv2*(t-m_T1);
00216 }
00217 else if (t > 0.0)
00218 {
00219 return 0.5*m_sa1*t*t;
00220 }
00221 else return 0.0;
00222 }
00223
00224 double RefValJS_PTP_Trajectory::ds_dt(double t) const
00225 {
00226 if (t >= m_T1 + m_T2 + m_T3)
00227 return 0.0;
00228 else if (t >= m_T1 + m_T2)
00229 {
00230 return m_sv2 + m_sa3*(t-m_T1-m_T2);
00231 }
00232 else if (t >= m_T1)
00233 {
00234 return m_sv2;
00235 }
00236 else if (t > 0.0)
00237 {
00238 return m_sa1*t;
00239 }
00240 else return 0.0;
00241 }
00242
00243
00244 std::vector<double> RefValJS_PTP_Trajectory::dr_ds(double s) const
00245 {
00246
00247 std::vector<double> result = m_trajectory.points.front().positions;
00248 if (s < 0.0 || s >= 1.0)
00249 {
00250 for(unsigned int j=0; j < result.size(); j++)
00251 result.at(j) = 0.0;
00252 }
00253 else
00254 {
00255
00256 vecd_it start = m_length_cumulated.begin();
00257 vecd_it end = m_length_cumulated.end();
00258 vecd_it it = upper_bound(start, end, s * m_length);
00259
00260 int i = int(it-start) - 1;
00261 double frac = (s * m_length - m_length_cumulated[i]) / m_length_parts[i];
00262
00263
00264
00265
00266
00267
00268
00269 std::vector<double> vi;
00270 std::vector<double> vii;
00271
00272 double step_s = m_stepSize / m_param_length;
00273
00274 if ( i == 0 )
00275 {
00276
00277 step_s = m_length_parts[0] / m_length;
00278 vi.resize(m_SplinePoints[i].size());
00279 for(unsigned int k = 0; k < m_SplinePoints[i].size(); k++)
00280 {
00281 vi.at(k) = (m_SplinePoints[1].at(k) - m_SplinePoints[0].at(k)) / step_s;
00282 }
00283 vii = vi;
00284
00285
00286
00287 } else
00288 if ( i == (int) m_SplinePoints.size() - 2 )
00289 {
00290
00291
00292
00293
00294 step_s = (m_length_parts[i]) / m_length;
00295 vii.resize(m_SplinePoints[i].size());
00296 for(unsigned int k = 0; k < m_SplinePoints[i].size(); k++)
00297 vii.at(k) = (m_SplinePoints[i+1].at(k) - m_SplinePoints[i].at(k)) / step_s;
00298 vi = vii;
00299 } else
00300 {
00301
00302 step_s = (m_length_parts[i]+m_length_parts[i-1]) / m_length;
00303 vi.resize(m_SplinePoints[i].size());
00304 for(unsigned int k = 0; k < m_SplinePoints[i].size(); k++)
00305 vi.at(k) = (m_SplinePoints[i+1].at(k) - m_SplinePoints[i-1].at(k)) / step_s;
00306 step_s = (m_length_parts[i]+m_length_parts[i+1]) / m_length;
00307 vii.resize(m_SplinePoints[i].size());
00308 for(unsigned int k = 0; k < m_SplinePoints[i].size(); k++)
00309 vii.at(k) = (m_SplinePoints[i+2].at(k) - m_SplinePoints[i].at(k)) / step_s;
00310 }
00311
00312
00313 result.resize(m_SplinePoints[i].size());
00314 for(unsigned int k = 0; k < m_SplinePoints[i].size(); k++)
00315 result.at(k) = vi.at(k) + (vii.at(k)-vi.at(k))*frac;
00316 }
00317
00318 return result;
00319 }
00320
00321
00322
00323