Commit 0b65bcbf authored by Joseph Mirabel's avatar Joseph Mirabel Committed by Joseph Mirabel
Browse files

Force instanciation of templated function integrate and difference.

parent b5a5a2b4
......@@ -107,6 +107,15 @@ namespace hpp {
(const DevicePtr_t& robot,
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result);
template void integrate<true, DefaultLieGroupMap>
(const DevicePtr_t& robot,
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result);
template void integrate<false, DefaultLieGroupMap>
(const DevicePtr_t& robot,
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result);
// TODO remove me. This is kept for backward compatibility
template void integrate<true, se3::LieGroupTpl>
(const DevicePtr_t& robot,
ConfigurationIn_t configuration,
......@@ -120,7 +129,7 @@ namespace hpp {
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result)
{
integrate<true, se3::LieGroupTpl> (robot, configuration, velocity, result);
integrate<true, DefaultLieGroupMap> (robot, configuration, velocity, result);
}
template <typename LieGroup>
......@@ -135,6 +144,12 @@ namespace hpp {
result.tail (dim) = u * q1.tail (dim) + (1-u) * q0.tail (dim);
}
template void interpolate<DefaultLieGroupMap> (const DevicePtr_t& robot,
ConfigurationIn_t q0,
ConfigurationIn_t q1,
const value_type& u,
ConfigurationOut_t result);
// TODO remove me. This is kept for backward compatibility
template void interpolate<se3::LieGroupTpl> (const DevicePtr_t& robot,
ConfigurationIn_t q0,
ConfigurationIn_t q1,
......@@ -159,6 +174,11 @@ namespace hpp {
result.tail (dim) = q1.tail (dim) - q2.tail (dim);
}
template void difference <DefaultLieGroupMap> (const DevicePtr_t& robot,
ConfigurationIn_t q1,
ConfigurationIn_t q2,
vectorOut_t result);
// TODO remove me. This is kept for backward compatibility
template void difference <se3::LieGroupTpl> (const DevicePtr_t& robot,
ConfigurationIn_t q1,
ConfigurationIn_t q2,
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment