Skip to content

Commit adcf974

Browse files
[feature-pose] Make it work on clang.
1 parent 9543eec commit adcf974

File tree

3 files changed

+28
-7
lines changed

3 files changed

+28
-7
lines changed

include/sot/core/feature-pose.hh

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,10 @@ private:
161161
/// \todo Intermediate variables for internal computations
162162
};
163163

164+
template < typename T >
165+
Vector6d convertVelocity(const MatrixHomogeneous &M,
166+
const MatrixHomogeneous &Mdes,
167+
const Vector &faNufafbDes);
164168
#if __cplusplus >= 201103L
165169
extern template class SOT_CORE_DLLAPI FeaturePose<SE3Representation>;
166170
extern template class SOT_CORE_DLLAPI FeaturePose<R3xSO3Representation>;

include/sot/core/feature-pose.hxx

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ template <Representation_t representation> struct LG_t {
5050
static const MatrixHomogeneous Id(MatrixHomogeneous::Identity());
5151

5252
template <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) {
128128
template <Representation_t representation>
129129
unsigned 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;

tests/features/test_feature_generic.cpp

Lines changed: 19 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,11 +32,28 @@
3232
#include <sot/core/feature-abstract.hh>
3333
#include <sot/core/feature-generic.hh>
3434
#include <sot/core/feature-pose.hh>
35-
#include <sot/core/feature-pose.hxx>
3635
#include <sot/core/gain-adaptive.hh>
3736
#include <sot/core/sot.hh>
3837
#include <sot/core/task.hh>
3938

39+
namespace dynamicgraph {
40+
namespace sot {
41+
42+
typedef pinocchio::CartesianProductOperation<
43+
pinocchio::VectorSpaceOperationTpl<3, double>,
44+
pinocchio::SpecialOrthogonalOperationTpl<3, double> >
45+
R3xSO3_t;
46+
typedef pinocchio::SpecialEuclideanOperationTpl<3, double> SE3_t;
47+
48+
namespace internal {
49+
template <Representation_t representation> struct LG_t {
50+
typedef typename boost::mpl::if_c<representation == SE3Representation, SE3_t,
51+
R3xSO3_t>::type type;
52+
};
53+
}
54+
}
55+
}
56+
4057
using namespace std;
4158
using namespace dynamicgraph::sot;
4259
using namespace dynamicgraph;
@@ -291,7 +308,7 @@ Vector toVector(const std::vector<MultiBound> &in) {
291308
template <Representation_t representation>
292309
class TestFeaturePose : public FeatureTestBase {
293310
public:
294-
typedef typename LG_t<representation>::type LieGroup_t;
311+
typedef typename dg::sot::internal::LG_t<representation>::type LieGroup_t;
295312
FeaturePose<representation> feature_;
296313
bool relative_;
297314
pinocchio::Model model_;

0 commit comments

Comments
 (0)