Unverified Commit 66518021 authored by Justin Carpentier's avatar Justin Carpentier Committed by GitHub
Browse files

Merge pull request #1342 from jcarpent/topic/urdf

Fix var name in CMake
parents 822fa051 e004d470
Pipeline #12253 passed with stage
in 141 minutes and 42 seconds
......@@ -67,11 +67,7 @@ We start with a simple program to compute the robot inverse dynamics. It is give
You can compile the C++ version by including Pinocchio and Eigen header directories.
\code g++ -std=c++11 $(pkg-config --cflags --libs pinocchio) overview-simple.cpp -o overview-simple \endcode
where `/path/to/pinocchio` is your chosen installation directory for Pinocchio.
If you do not know Eigen's installation path, you can retrive it with `pkg-config --cflags eigen3`.
On Linux, it will usually be something like `/usr/include/eigen3/`.
\code g++ -std=c++11 overview-simple.cpp -o overview-simple $(pkg-config --cflags --libs pinocchio) \endcode
Once your code is compiled, you might then run it using
......@@ -138,7 +134,7 @@ in Python.
In similar way than the previous example, you simple need to do:
\code g++ -std=c++11 $(pkg-config --cflags --libs pinocchio) overview-urdf.cpp -o overview-urdf \endcode
\code g++ -std=c++11 overview-urdf.cpp -o overview-urdf $(pkg-config --cflags --libs pinocchio) \endcode
The program typically runs with a UR5 URDF description, that can be found for example in this repository https://github.com/humanoid-path-planner/ur_description
......
......@@ -17,7 +17,7 @@ SET(${PROJECT_NAME}_EXAMPLES
interpolation-SE3
)
IF(BUILD_WITH_UDRF_SUPPORT)
IF(BUILD_WITH_URDF_SUPPORT)
LIST(APPEND ${PROJECT_NAME}_EXAMPLES
overview-urdf
build-reduced-model
......@@ -29,7 +29,7 @@ IF(BUILD_WITH_UDRF_SUPPORT)
ENDIF()
IF(BUILD_ADVANCED_TESTING)
IF(BUILD_WITH_UDRF_SUPPORT)
IF(BUILD_WITH_URDF_SUPPORT)
LIST(APPEND ${PROJECT_NAME}_EXAMPLES
multiprecision
)
......@@ -37,7 +37,7 @@ IF(BUILD_ADVANCED_TESTING)
ENDIF(BUILD_ADVANCED_TESTING)
IF(hpp-fcl_FOUND)
IF(BUILD_WITH_UDRF_SUPPORT)
IF(BUILD_WITH_URDF_SUPPORT)
LIST(APPEND ${PROJECT_NAME}_EXAMPLES
collisions
)
......@@ -54,9 +54,9 @@ FOREACH(EXAMPLE ${${PROJECT_NAME}_EXAMPLES})
ADD_PINOCCHIO_CPP_EXAMPLE(${EXAMPLE})
ENDFOREACH(EXAMPLE ${${PROJECT_NAME}_EXAMPLES})
IF(BUILD_ADVANCED_TESTING AND BUILD_WITH_UDRF_SUPPORT)
IF(BUILD_ADVANCED_TESTING AND BUILD_WITH_URDF_SUPPORT)
SET_PROPERTY(TARGET example-cpp-multiprecision PROPERTY CXX_STANDARD 11)
ENDIF(BUILD_ADVANCED_TESTING AND BUILD_WITH_UDRF_SUPPORT)
ENDIF(BUILD_ADVANCED_TESTING AND BUILD_WITH_URDF_SUPPORT)
IF(BUILD_PYTHON_INTERFACE)
SET(${PROJECT_NAME}_PYTHON_EXAMPLES
......@@ -85,11 +85,11 @@ IF(BUILD_PYTHON_INTERFACE)
display-shapes
simulation-inverted-pendulum
)
IF(BUILD_WITH_UDRF_SUPPORT)
IF(BUILD_WITH_URDF_SUPPORT)
LIST(APPEND ${PROJECT_NAME}_PYTHON_EXAMPLES
collisions
)
ENDIF(BUILD_WITH_UDRF_SUPPORT)
ENDIF(BUILD_WITH_URDF_SUPPORT)
ENDIF(hpp-fcl_FOUND)
FOREACH(EXAMPLE ${${PROJECT_NAME}_PYTHON_EXAMPLES})
......
......@@ -4,15 +4,15 @@ This directory contains minimal examples on how to use **Pinocchio** with the Py
## Loading a model
- Loading an embeded Model: `python -i overview-simple.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g overview-simple.cpp -o overview-simple && ./overview-simple`
- Loading a URDF model: `python -i overview-urdf.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g overview-urdf.cpp -o overview-urdf && ./overview-urdf`
- Loading an embeded Model: `python -i overview-simple.py` and in C++ `g++ overview-simple.cpp -o overview-simple $(pkg-config --cflags --libs pinocchio) && ./overview-simple`
- Loading a URDF model: `python -i overview-urdf.py` and in C++ `g++ -g overview-urdf.cpp -o overview-urdf $(pkg-config --cflags --libs pinocchio) && ./overview-urdf`
- Using RobotWrapper to encapsulate a URDF model: `python -i robot-wrapper-viewer.py`
## Computes analytical derivatives of rigid body dynamics algorithms
- Computing forward kinematics derivatives: `python -i kinematics-derivatives.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g kinematics-derivatives.cpp -o kinematics-derivatives && ./kinematics-derivatives`
- Computing forward dynamics derivatives: `python -i forward-dynamics-derivatives.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g forward-dynamics-derivatives.cpp -o forward-dynamics-derivatives && ./forward-dynamics-derivatives`
- Computing inverse dynamics derivatives: `python -i inverse-dynamics-derivatives.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g inverse-dynamics-derivatives.cpp -o inverse-dynamics-derivatives && ./inverse-derivatives`
- Computing forward kinematics derivatives: `python -i kinematics-derivatives.py` and in C++ `g++ kinematics-derivatives.cpp -o kinematics-derivatives $(pkg-config --cflags --libs pinocchio) && ./kinematics-derivatives`
- Computing forward dynamics derivatives: `python -i forward-dynamics-derivatives.py` and in C++ `g++ -I -g forward-dynamics-derivatives.cpp -o forward-dynamics-derivatives $(pkg-config --cflags --libs pinocchio) && ./forward-dynamics-derivatives`
- Computing inverse dynamics derivatives: `python -i inverse-dynamics-derivatives.py` and in C++ `g++ inverse-dynamics-derivatives.cpp -o inverse-dynamics-derivatives $(pkg-config --cflags --libs pinocchio) && ./inverse-derivatives`
## Displaying the models
......@@ -26,13 +26,13 @@ For the following examples, you should have [gepetto-gui](https://github.com/Gep
**Pinocchio** encapsulates [FCL](https://github.com/humanoid-path-planner/hpp-fcl) in it. You can then do collision checking or distance computations with only few lines of code.
- Check collisions using [FCL](https://github.com/humanoid-path-planner/hpp-fcl): `python -i collisions.py` and in C++ `g++ -I $(pkg-config --cflags pinocchio) -g collision.cpp -o collision && ./collision`
- Check collisions using [FCL](https://github.com/humanoid-path-planner/hpp-fcl): `python -i collisions.py` and in C++ `g++ collision.cpp -o collision $(pkg-config --cflags --libs pinocchio) && ./collision`
## Multiprecision arithmetic
Thanks to the full templatization of the project, **Pinocchio** is able to perform full precision arithmetic (via Boost.Multiprecision for instance).
- Multiprecision example: `g++ -I $(pkg-config --cflags pinocchio) -g multiprecision.cpp -o multiprecision && ./multiprecision`
- Multiprecision example: `g++ multiprecision.cpp -o multiprecision $(pkg-config --cflags --libs pinocchio) && ./multiprecision`
## Adding new examples
......
......@@ -25,7 +25,7 @@ namespace pinocchio
{
struct UrdfGeomVisitorBase
{
typedef FrameTpl<urdf_value_type, 0> Frame;
typedef FrameTpl<urdf_scalar_type, 0> Frame;
virtual Frame getBodyFrame (const std::string& name, FrameIndex& fid) const = 0;
};
......@@ -46,7 +46,7 @@ namespace pinocchio
}
fid = model.getFrameId(link_name, BODY);
PINOCCHIO_CHECK_INPUT_ARGUMENT(model.frames[fid].type == BODY);
return model.frames[fid].template cast<urdf_value_type>();
return model.frames[fid].template cast<urdf_scalar_type>();
}
};
......
......@@ -5,6 +5,7 @@
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/parsers/urdf/utils.hpp"
#include "pinocchio/parsers/urdf/model.hxx"
#include <urdf_model/model.h>
#include <urdf_parser/urdf_parser.h>
......
......@@ -20,7 +20,7 @@ namespace pinocchio
{
namespace details
{
typedef double urdf_value_type;
typedef double urdf_scalar_type;
template<typename _Scalar, int Options>
class UrdfVisitorBaseTpl {
......@@ -378,7 +378,7 @@ namespace pinocchio
{
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, root_joint);
if (verbose) visitor.log = &std::cout;
parseRootTree(filename, visitor);
details::parseRootTree(filename, visitor);
return model;
}
......@@ -390,7 +390,7 @@ namespace pinocchio
{
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTree(filename, visitor);
details::parseRootTree(filename, visitor);
return model;
}
......@@ -403,7 +403,7 @@ namespace pinocchio
{
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, rootJoint);
if (verbose) visitor.log = &std::cout;
parseRootTreeFromXML(xmlStream, visitor);
details::parseRootTreeFromXML(xmlStream, visitor);
return model;
}
......@@ -415,7 +415,7 @@ namespace pinocchio
{
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTreeFromXML(xmlStream, visitor);
details::parseRootTreeFromXML(xmlStream, visitor);
return model;
}
......@@ -429,7 +429,7 @@ namespace pinocchio
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, rootJoint);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
details::parseRootTree(urdfTree.get(), visitor);
return model;
}
......@@ -442,7 +442,7 @@ namespace pinocchio
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
details::parseRootTree(urdfTree.get(), visitor);
return model;
}
......@@ -457,7 +457,7 @@ namespace pinocchio
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, rootJoint);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
details::parseRootTree(urdfTree.get(), visitor);
return model;
}
......@@ -470,7 +470,7 @@ namespace pinocchio
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
details::parseRootTree(urdfTree.get(), visitor);
return model;
}
#endif
......
Markdown is supported
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