Skip to content
Snippets Groups Projects
Commit 9daceeca authored by Valenza Florian's avatar Valenza Florian
Browse files

[FixBug][C++]Fixed compilation errors dur to change in API

parent 3054137b
No related branches found
No related tags found
No related merge requests found
......@@ -182,7 +182,7 @@ hpp::model::HumanoidRobotPtr_t humanoidRobot =
timer.tic();
SMOOTH(NBT)
{
updateCollisionGeometry(romeo_model,romeo_data,romeo_model_geom,romeo_data_geom,qs_romeo_pino[_smooth], true);
updateGeometryPlacements(romeo_model,romeo_data,romeo_model_geom,romeo_data_geom,qs_romeo_pino[_smooth]);
}
double compute_forward_kinematics_time = timer.toc(StackTicToc::US)/NBT;
std::cout << "Update Collision Geometry < true > (K) = \t" << compute_forward_kinematics_time << " " << StackTicToc::unitName(StackTicToc::US) << std::endl;
......
......@@ -330,7 +330,7 @@ BOOST_AUTO_TEST_CASE ( hrp2_mesh_distance)
/// ********** Pinocchio ********** ///
/// ********************************* ///
/// ********************************* ///
// Building the model in pinocchio and compute kinematics/geometry for configuration q_pino
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo.urdf";
......@@ -399,10 +399,10 @@ BOOST_AUTO_TEST_CASE ( hrp2_mesh_distance)
std::cout << "comparison between " << body1 << " and " << body2 << std::endl;
fcl::DistanceResult dist_pin = data_geom.computeDistance( robot.second.getGeomId(body1),
se3::DistanceResult dist_pin = data_geom.computeDistance( robot.second.getGeomId(body1),
robot.second.getGeomId(body2));
Distance_t distance_pin ( dist_pin);
Distance_t distance_pin(dist_pin.fcl_distance_result);
distance_hpp.checkClose(distance_pin);
}
}
......@@ -415,7 +415,7 @@ BOOST_AUTO_TEST_SUITE_END ()
JointPositionsMap_t fillPinocchioJointPositions(const se3::Data & data)
{
JointPositionsMap_t result;
for (int i = 0; i < data.model.nbody; ++i)
for (se3::Model::Index i = 0; i < (se3::Model::Index)data.model.nbody; ++i)
{
result[data.model.getJointName(i)] = data.oMi[i];
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment