Verified Commit d5b50fb5 authored by Justin Carpentier's avatar Justin Carpentier
Browse files

all: add PINOCCHIO_ prefix at the begining of each MACRO naming

parent a42477a7
......@@ -106,20 +106,20 @@ ENDIF(CPPAD_FOUND)
# Special care of urdfdom version
IF(URDFDOM_FOUND)
IF(${URDFDOM_VERSION} VERSION_LESS "0.3.0")
ADD_DEFINITIONS(-DURDFDOM_COLLISION_WITH_GROUP_NAME)
PKG_CONFIG_APPEND_CFLAGS("-DURDFDOM_COLLISION_WITH_GROUP_NAME")
ADD_DEFINITIONS(-DPINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME)
PKG_CONFIG_APPEND_CFLAGS("-DPINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME")
ENDIF(${URDFDOM_VERSION} VERSION_LESS "0.3.0")
# defines types from version 0.4.0
IF(NOT ${URDFDOM_VERSION} VERSION_LESS "0.4.0")
ADD_DEFINITIONS(-DURDFDOM_TYPEDEF_SHARED_PTR)
PKG_CONFIG_APPEND_CFLAGS("-DURDFDOM_TYPEDEF_SHARED_PTR")
ADD_DEFINITIONS(-DPINOCCHIO_URDFDOM_TYPEDEF_SHARED_PTR)
PKG_CONFIG_APPEND_CFLAGS("-DPINOCCHIO_URDFDOM_TYPEDEF_SHARED_PTR")
ENDIF(NOT ${URDFDOM_VERSION} VERSION_LESS "0.4.0")
# std::shared_ptr appears from version 1.0.0
IF(${URDFDOM_VERSION} VERSION_GREATER "0.4.2")
ADD_DEFINITIONS(-DURDFDOM_USE_STD_SHARED_PTR)
PKG_CONFIG_APPEND_CFLAGS("-DURDFDOM_USE_STD_SHARED_PTR")
ADD_DEFINITIONS(-DPINOCCHIO_URDFDOM_USE_STD_SHARED_PTR)
PKG_CONFIG_APPEND_CFLAGS("-DPINOCCHIO_URDFDOM_USE_STD_SHARED_PTR")
ENDIF(${URDFDOM_VERSION} VERSION_GREATER "0.4.2")
ENDIF(URDFDOM_FOUND)
......@@ -130,8 +130,8 @@ IF(BUILD_WITH_LUA_SUPPORT)
IF(LUA5_2_FOUND)
SET(LUA5_FOUND TRUE)
SET(LUA5_PACKAGE "lua5.2")
ADD_DEFINITIONS(-DLUA_VERSION_GREATER_5_2)
PKG_CONFIG_APPEND_CFLAGS("-DLUA_VERSION_GREATER_5_2")
ADD_DEFINITIONS(-DPINOCCHIO_LUA_VERSION_GREATER_5_2)
PKG_CONFIG_APPEND_CFLAGS("-DPINOCCHIO_LUA_VERSION_GREATER_5_2")
ELSE(LUA5_2_FOUND)
ADD_OPTIONAL_DEPENDENCY("lua5.1")
IF(LUA5_1_FOUND)
......@@ -171,8 +171,8 @@ FILE(GLOB_RECURSE HEADERS
)
IF(URDFDOM_FOUND)
ADD_DEFINITIONS(-DWITH_URDFDOM)
LIST(APPEND CFLAGS_DEPENDENCIES "-DWITH_URDFDOM")
ADD_DEFINITIONS(-DPINOCCHIO_WITH_URDFDOM)
LIST(APPEND CFLAGS_DEPENDENCIES "-DPINOCCHIO_WITH_URDFDOM")
ELSE(URDFDOM_FOUND)
LIST(REMOVE_ITEM HEADERS
${PROJECT_SOURCE_DIR}/src/parsers/urdf.hpp
......@@ -185,8 +185,8 @@ ENDIF(URDFDOM_FOUND)
IF(HPP_FCL_FOUND)
ADD_DEFINITIONS(-DWITH_HPP_FCL)
LIST(APPEND CFLAGS_DEPENDENCIES "-DWITH_HPP_FCL")
ADD_DEFINITIONS(-DPINOCCHIO_WITH_HPP_FCL)
LIST(APPEND CFLAGS_DEPENDENCIES "-DPINOCCHIO_WITH_HPP_FCL")
ELSE(HPP_FCL_FOUND)
LIST(REMOVE_ITEM HEADERS
${PROJECT_SOURCE_DIR}/src/spatial/fcl-pinocchio-conversions.hpp
......@@ -194,8 +194,8 @@ ELSE(HPP_FCL_FOUND)
ENDIF(HPP_FCL_FOUND)
IF(LUA5_FOUND)
ADD_DEFINITIONS(-DWITH_LUA5)
LIST(APPEND CFLAGS_DEPENDENCIES "-DWITH_LUA5")
ADD_DEFINITIONS(-DPINOCCHIO_WITH_LUA5)
LIST(APPEND CFLAGS_DEPENDENCIES "-DPINOCCHIO_WITH_LUA5")
ELSE(LUA5_FOUND)
LIST(REMOVE_ITEM HEADERS
${PROJECT_SOURCE_DIR}/src/parsers/lua.hpp
......
......@@ -61,9 +61,9 @@ int main()
se3::Model model;
se3::urdf::buildModel(romeo_filename, se3::JointModelFreeFlyer(),model);
se3::GeometryModel geom_model; se3::urdf::buildGeom(model, romeo_filename, COLLISION, geom_model, package_dirs);
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
geom_model.addAllCollisionPairs();
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
Data data(model);
GeometryData geom_data(geom_model);
......@@ -95,7 +95,7 @@ int main()
double update_col_time = timer.toc(PinocchioTicToc::US)/NBT - geom_time;
std::cout << "Update Collision Geometry < false > = \t" << update_col_time << " " << PinocchioTicToc::unitName(PinocchioTicToc::US) << std::endl;
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
timer.tic();
SMOOTH(NBT)
{
......@@ -129,6 +129,6 @@ int main()
std::cout << "Compute distance between two geometry objects (mean time) = \t" << computeDistancesTime / double(geom_model.collisionPairs.size())
<< " " << PinocchioTicToc::unitName(PinocchioTicToc::US) << " " << geom_model.collisionPairs.size() << " col pairs" << std::endl;
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
return 0;
}
......@@ -40,7 +40,7 @@ namespace se3
"Update the placement of the collision objects according to the current joint placement stored in data."
);
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
bp::def("computeCollision",computeCollision,
bp::args("geometry model", "geometry data", "collision pair index"),
"Check if the collision objects of a collision pair for a given Geometry Model and Data are in collision."
......@@ -79,7 +79,7 @@ namespace se3
"Update the geometry for a given configuration and"
"compute the distance between each collision pair"
);
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
}
} // namespace python
} // namespace se3
......@@ -47,9 +47,9 @@ namespace se3
// Expose algorithms
void exposeAlgorithms();
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
void exposeFCL();
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
} // namespace python
} // namespace se3
......
......@@ -62,9 +62,9 @@ BOOST_PYTHON_MODULE(libpinocchio_pywrap)
exposeAlgorithms();
exposeParsers();
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
exposeFCL();
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
exposeVersion();
......
......@@ -73,7 +73,7 @@ namespace se3
.def_readonly("oMg",
&GeometryData::oMg,
"Vector of collision objects placement relative to the world.")
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
.def_readonly("activeCollisionPairs",
&GeometryData::activeCollisionPairs,
"Vector of active CollisionPairs")
......@@ -104,7 +104,7 @@ namespace se3
bp::args("pairIndex (int)"),
"Deactivate pair ID <pairIndex> in geomModel.collisionPairs.")
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
;
}
......
......@@ -56,7 +56,7 @@ namespace se3
"Add a GeometryObject to a GeometryModel and set its parent joint by reading its value in model")
.def("getGeometryId",&GeometryModel::getGeometryId)
.def("existGeometryName",&GeometryModel::existGeometryName)
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
.add_property("collisionPairs",
&GeometryModel::collisionPairs,
"Vector of collision pairs.")
......@@ -80,7 +80,7 @@ namespace se3
bp::args("co1 (index)","co2 (index)"),
"Return the index of a collision pair given by the index of the two collision objects exists or not."
" Remark: co1 < co2")
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
;
}
......
......@@ -56,14 +56,14 @@ namespace se3
.def_readonly("overrideMaterial", &GeometryObject::overrideMaterial, "Boolean that tells whether material information is stored in Geometry object")
.def_readonly("meshTexturePath", &GeometryObject::meshTexturePath, "Absolute path to the mesh texture file")
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
.def("CreateCapsule", &GeometryObjectPythonVisitor::maker_capsule)
.staticmethod("CreateCapsule")
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
;
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
static GeometryObject maker_capsule( const double radius , const double length)
{
return GeometryObject("",FrameIndex(0),JointIndex(0),
......@@ -71,7 +71,7 @@ namespace se3
SE3::Identity());
}
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
static void expose()
{
......
......@@ -23,16 +23,16 @@
#include "pinocchio/bindings/python/multibody/data.hpp"
#ifdef WITH_URDFDOM
#ifdef PINOCCHIO_WITH_URDFDOM
#include "pinocchio/parsers/urdf.hpp"
#endif
#include "pinocchio/bindings/python/multibody/geometry-model.hpp"
#include "pinocchio/bindings/python/multibody/geometry-data.hpp"
#ifdef WITH_LUA5
#ifdef PINOCCHIO_WITH_LUA5
#include "pinocchio/parsers/lua.hpp"
#endif // #ifdef WITH_LUA5
#endif // #ifdef PINOCCHIO_WITH_LUA5
#include "pinocchio/parsers/srdf.hpp"
......@@ -51,7 +51,7 @@ namespace se3
};
#ifdef WITH_URDFDOM
#ifdef PINOCCHIO_WITH_URDFDOM
static Model buildModelFromUrdf(const std::string & filename)
{
......@@ -128,9 +128,9 @@ namespace se3
return geometry_model;
}
#endif // #ifdef WITH_URDFDOM
#endif // #ifdef PINOCCHIO_WITH_URDFDOM
#ifdef WITH_LUA5
#ifdef PINOCCHIO_WITH_LUA5
static Model buildModelFromLua(const std::string & filename,
bool ff,
bool verbose
......@@ -140,7 +140,7 @@ namespace se3
model = se3::lua::buildModel (filename, ff, verbose);
return model;
}
#endif // #ifdef WITH_LUA5
#endif // #ifdef PINOCCHIO_WITH_LUA5
/* --- Expose --------------------------------------------------------- */
static void expose();
......@@ -148,7 +148,7 @@ namespace se3
inline void ParsersPythonVisitor::expose()
{
#ifdef WITH_URDFDOM
#ifdef PINOCCHIO_WITH_URDFDOM
bp::def("buildModelFromUrdf",
......@@ -198,7 +198,7 @@ namespace se3
bp::args("Model to assosiate the Geometry","filename (string)"),
"Parse the URDF file given in input looking for the geometry of the given Model and return a proper pinocchio geometry model ");
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
bp::def("removeCollisionPairs",
static_cast<void (*)(const Model &, GeometryModel &, const std::string &, const bool)>(&srdf::removeCollisionPairs),
......@@ -210,16 +210,16 @@ namespace se3
bp::args("Model", "GeometryModel (where pairs are removed)","string containing the XML-SRDF", "verbosity"),
"Parse an SRDF file in order to desactivte collision pairs for a specific GeometryModel.");
#endif // #ifdef WITH_HPP_FCL
#endif // #ifdef WITH_URDFDOM
#endif // #ifdef PINOCCHIO_WITH_HPP_FCL
#endif // #ifdef PINOCCHIO_WITH_URDFDOM
#ifdef WITH_LUA5
#ifdef PINOCCHIO_WITH_LUA5
bp::def("buildModelFromLua",buildModelFromLua,
bp::args("Filename (string)",
"Free flyer (bool, false for a fixed robot)",
"Verbose option "),
"Parse the URDF file given in input and return a proper pinocchio model");
#endif // #ifdef WITH_LUA5
#endif // #ifdef PINOCCHIO_WITH_LUA5
bp::def("getNeutralConfiguration",
static_cast<Model::ConfigVectorType (*)(Model &, const std::string &, const bool)>(&srdf::getNeutralConfiguration),
......
......@@ -50,7 +50,7 @@ namespace se3
return model;
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
static GeometryModel buildSampleGeometryModelManipulator(const Model& model)
{
GeometryModel geom;
......@@ -73,7 +73,7 @@ namespace se3
return model;
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
static GeometryModel buildSampleGeometryModelHumanoid(const Model& model)
{
GeometryModel geom;
......@@ -104,7 +104,7 @@ namespace se3
"Generate a (hard-coded) model of a simple manipulator."
);
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
bp::def("buildSampleGeometryModelManipulator",
static_cast <GeometryModel (*) (const Model&)> (&SampleModelsPythonVisitor::buildSampleGeometryModelManipulator),
bp::args("Model (model)"),
......@@ -123,7 +123,7 @@ namespace se3
"Generate a (hard-coded) model of a simple humanoid."
);
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
bp::def("buildSampleGeometryModelHumanoid",
static_cast <GeometryModel (*) (const Model&)> (&SampleModelsPythonVisitor::buildSampleGeometryModelHumanoid),
bp::args("Model (model)"),
......
......@@ -63,7 +63,7 @@ namespace se3
const GeometryModel & geomModel,
GeometryData & geomData);
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
///
/// \brief Compute the collision status between a *SINGLE* collision pair.
......@@ -196,7 +196,7 @@ namespace se3
inline void computeBodyRadius(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const GeometryModel & geomModel,
GeometryData & geomData);
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
///
/// Append geomModel2 to geomModel1
......
......@@ -51,12 +51,12 @@ namespace se3
const Model::JointIndex & joint = geomModel.geometryObjects[i].parentJoint;
if (joint>0) geomData.oMg[i] = (data.oMi[joint] * geomModel.geometryObjects[i].placement);
else geomData.oMg[i] = geomModel.geometryObjects[i].placement;
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
geomData.collisionObjects[i].setTransform( toFclTransform3f(geomData.oMg[i]) );
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
}
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
/* --- COLLISIONS ----------------------------------------------------------------- */
/* --- COLLISIONS ----------------------------------------------------------------- */
......@@ -283,7 +283,7 @@ namespace se3
}
#undef SE3_GEOM_AABB
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
/* --- APPEND GEOMETRY MODEL ----------------------------------------------------------- */
......
//
// Copyright (c) 2018 INRIA
//
// This file is part of Pinocchio
// Pinocchio is free software: you can redistribute it
// and/or modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation, either version
// 3 of the License, or (at your option) any later version.
//
// Pinocchio is distributed in the hope that it will be
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
// General Lesser Public License for more details. You should have
// received a copy of the GNU Lesser General Public License along with
// Pinocchio If not, see
// <http://www.gnu.org/licenses/>.
#ifndef __se3_deprecated_macros_hpp__
#define __se3_deprecated_macros_hpp__
#ifdef PINOCCHIO_WITH_HPP_FCL
#ifndef WITH_HPP_FCL
#define WITH_HPP_FCL // for backward compatibility
#endif
#ifndef PINOCCHIO_DISABLE_DEPRECATED_MACRO_WARNING
#pragma message("'WITH_HPP_FCL' is deprecated. Please use PINOCCHIO_WITH_HPP_FCL instead.")
#endif
#endif
#ifdef PINOCCHIO_WITH_URDFDOM
#ifndef WITH_URDFDOM
#define WITH_URDFDOM // for backward compatibility
#endif
#ifndef PINOCCHIO_DISABLE_DEPRECATED_MACRO_WARNING
#pragma message("'WITH_URDFDOM' is deprecated. Please use PINOCCHIO_WITH_URDFDOM instead.")
#endif
#endif
#ifdef PINOCCHIO_WITH_LUA5
#ifndef WITH_LUA5
#define WITH_LUA5 // for backward compatibility
#endif
#ifndef PINOCCHIO_DISABLE_DEPRECATED_MACRO_WARNING
#pragma message("'WITH_LUA5' is deprecated. Please use PINOCCHIO_WITH_LUA5 instead.")
#endif
#endif
#endif // ifndef __se3_deprecated_macros_hpp__
//
// Copyright (c) 2018 CNRS
// Copyright (c) 2018 CNRS INRIA
//
// This file is part of Pinocchio
// Pinocchio is free software: you can redistribute it
......@@ -19,6 +19,7 @@
#define __se3_fwd_hpp__
#include "pinocchio/macros.hpp"
#include "pinocchio/deprecated-macros.hpp"
#include "pinocchio/deprecated.hpp"
#include "pinocchio/warning.hpp"
#include "pinocchio/config.hpp"
......
......@@ -22,7 +22,7 @@
#include "pinocchio/multibody/fwd.hpp"
#include "pinocchio/container/aligned-vector.hpp"
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
#include <hpp/fcl/collision_object.h>
#include <hpp/fcl/collision.h>
#include <hpp/fcl/distance.h>
......@@ -53,7 +53,7 @@ namespace se3
}; // struct CollisionPair
#ifndef WITH_HPP_FCL
#ifndef PINOCCHIO_WITH_HPP_FCL
namespace fcl
{
......@@ -74,7 +74,7 @@ namespace se3
}
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
enum GeometryType
{
......
......@@ -53,7 +53,7 @@ namespace se3
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
inline bool operator == (const fcl::CollisionObject & lhs, const fcl::CollisionObject & rhs)
{
......@@ -62,7 +62,7 @@ namespace se3
&& lhs.getAABB().max_ == rhs.getAABB().max_;
}
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
inline bool operator==(const GeometryObject & lhs, const GeometryObject & rhs)
{
......
......@@ -142,7 +142,7 @@ namespace se3
*/
PINOCCHIO_DEPRECATED const std::string & getGeometryName(const GeomIndex index) const;
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
///
/// \brief Add a collision pair into the vector of collision_pairs.
/// The method check before if the given CollisionPair is already included.
......@@ -189,7 +189,7 @@ namespace se3
///
PairIndex findCollisionPair(const CollisionPair & pair) const;
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
friend std::ostream& operator<<(std::ostream & os, const GeometryModel & model_geom);
}; // struct GeometryModel
......@@ -212,7 +212,7 @@ namespace se3
///
container::aligned_vector<SE3> oMg;
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
///
/// \brief Collision objects (ie a fcl placed geometry).
///
......@@ -273,12 +273,12 @@ namespace se3
/// Outer objects can be seen as geometry objects that may often be
/// obstacles to the Inner objects of given joint
std::map < JointIndex, GeomIndexList > outerObjects;
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
GeometryData(const GeometryModel & geomModel);
~GeometryData() {};
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
/// Fill both innerObjects and outerObjects maps, from vectors collisionObjects and
/// collisionPairs.
......@@ -308,7 +308,7 @@ namespace se3
/// \sa activateCollisionPair
void deactivateCollisionPair(const PairIndex pairId);
#endif //WITH_HPP_FCL
#endif //PINOCCHIO_WITH_HPP_FCL
friend std::ostream & operator<<(std::ostream & os, const GeometryData & geomData);
}; // struct GeometryData
......
......@@ -30,7 +30,7 @@ namespace se3
inline GeometryData::GeometryData(const GeometryModel & modelGeom)
: oMg(modelGeom.ngeoms)
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
, activeCollisionPairs(modelGeom.collisionPairs.size(), true)
, distanceRequest (true, 0, 0, fcl::GST_INDEP)
, distanceResults(modelGeom.collisionPairs.size())
......@@ -49,7 +49,7 @@ namespace se3
}
#else
{}
#endif // WITH_HPP_FCL
#endif // PINOCCHIO_WITH_HPP_FCL
template<typename S2, int O2, template<typename,int> class JointCollectionTpl>
GeomIndex GeometryModel::addGeometryObject(const GeometryObject & object,
......@@ -132,7 +132,7 @@ namespace se3
// std::cout << "outer object already added" << std::endl;
// }
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
inline void GeometryData::fillInnerOuterObjectMaps(const GeometryModel & geomModel)
{
innerObjects.clear();
......@@ -162,7 +162,7 @@ namespace se3
inline std::ostream & operator<< (std::ostream & os, const GeometryData & geomData)
{
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
os << "Number of collision pairs = " << geomData.activeCollisionPairs.size() << std::endl;
for(PairIndex i=0;i<(PairIndex)(geomData.activeCollisionPairs.size());++i)
......@@ -177,7 +177,7 @@ namespace se3
return os;
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
inline void GeometryModel::addCollisionPair (const CollisionPair & pair)
{
......@@ -240,7 +240,7 @@ namespace se3
activeCollisionPairs[pairId] = false;
}
#endif //WITH_HPP_FCL
#endif //PINOCCHIO_WITH_HPP_FCL
} // namespace se3
/// @endcond
......
......@@ -536,7 +536,7 @@ size_t LuaTableNode::length()
if (stackQueryValue())
{
#ifdef LUA_VERSION_GREATER_5_2
#ifdef PINOCCHIO_LUA_VERSION_GREATER_5_2
result = lua_rawlen(luaTable->L, -1);
#else
result = lua_objlen(luaTable->L, -1);
......@@ -699,7 +699,7 @@ int LuaTable::length()
}
size_t result = 0;
#ifdef LUA_VERSION_GREATER_5_2
#ifdef PINOCCHIO_LUA_VERSION_GREATER_5_2
result = lua_rawlen(L, -1);
#else
result = lua_objlen(L, -1);
......
......@@ -183,7 +183,7 @@ namespace se3
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
/* Add a 6DOF manipulator shoulder-elbow-wrist geometries to an existing model.
* <model> is the the kinematic chain, constant.
* <geom> is the geometry model where the new geoms are added.
......@@ -241,7 +241,7 @@ namespace se3
void manipulator(Model & model) { addManipulator(model); }
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
void manipulatorGeometries(const Model & model, GeometryModel & geom)
{ addManipulatorGeometries(model,geom); }
#endif
......@@ -316,7 +316,7 @@ namespace se3
addManipulator(model,chest,SE3(rotate(M_PI,Vector3d::UnitX()),Vector3d(0, 0.3, 1.)),"larm");
}
#ifdef WITH_HPP_FCL
#ifdef PINOCCHIO_WITH_HPP_FCL
void humanoidGeometries(const Model & model, GeometryModel & geom)
{
addManipulatorGeometries(model,geom,"rleg");
......