@@ -50,7 +50,7 @@ template <Representation_t representation> struct LG_t {
5050static const MatrixHomogeneous Id (MatrixHomogeneous::Identity());
5151
5252template <Representation_t representation>
53- FeaturePose<representation>::FeaturePose(const string &pointName)
53+ FeaturePose<representation>::FeaturePose(const std:: string &pointName)
5454 : FeatureAbstract(pointName),
5555 oMja (NULL , CLASS_NAME + " (" + name + " )::input(matrixHomo)::oMja" ),
5656 jaMfa(NULL , CLASS_NAME + " (" + name + " )::input(matrixHomo)::jaMfa" ),
@@ -128,7 +128,7 @@ static inline void check(const FeaturePose<representation> &ft) {
128128template <Representation_t representation>
129129unsigned int &FeaturePose<representation>::getDimension(unsigned int &dim,
130130 int time) {
131- sotDEBUG (25 ) << " # In {" << endl;
131+ sotDEBUG (25 ) << " # In {" << std:: endl;
132132
133133 const Flags &fl = selectionSIN.access (time);
134134
@@ -137,7 +137,7 @@ unsigned int &FeaturePose<representation>::getDimension(unsigned int &dim,
137137 if (fl (i))
138138 dim++;
139139
140- sotDEBUG (25 ) << " # Out }" << endl;
140+ sotDEBUG (25 ) << " # Out }" << std:: endl;
141141 return dim;
142142}
143143
@@ -259,8 +259,8 @@ Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
259259// This function is responsible of converting the input velocity expressed with
260260// SE(3) convention onto a velocity expressed with the convention of this
261261// feature (R^3xSO(3) or SE(3)), in the right frame.
262- template <typename internal::LG_t >
263- Vector6d convertVelocity (const MatrixHomogeneous &M,
262+ template <>
263+ Vector6d convertVelocity<SE3_t> (const MatrixHomogeneous &M,
264264 const MatrixHomogeneous &Mdes,
265265 const Vector &faNufafbDes) {
266266 (void )M;
0 commit comments