**Pinocchio** instatiates state-of-the-art Rigid Body Algotithms for poly-articulated systems based on revisited Roy Featherstone's algorithms.
**Pinocchio** instantiates state-of-the-art Rigid Body Algorithms for poly-articulated systems based on revisited Roy Featherstone's algorithms.
In addition, **Pinocchio** instantiates analytical derivatives of the main Rigid-Body Algorithms like the Recursive Newton-Euler Algorithms or the Articulated-Body Algorithm.
**Pinocchio** is first tailored for legged robotics applications, but it can be used in extra contextes.
It is built upon Eigen for linear algebra and FCL for collision detections. **Pinocchio** comes with a Python interface for fast code protyping.
**Pinocchio** is first tailored for legged robotics applications, but it can be used in extra contexts.
It is built upon Eigen for linear algebra and FCL for collision detection. **Pinocchio** comes with a Python interface for fast code prototyping.
**Pinocchio** is now at the hearth of various robotics softwares as the [Stack-of-Tasks](http://stack-of-tasks.github.io) or the [Humanoid Path Planner](https://humanoid-path-planner.github.io/hpp-doc).
...
...
@@ -27,7 +27,7 @@ We provide some basic examples on how to use **Pinocchio** in Python in the [exa
## Tutorials
**Pinocchio** is comming with a large bunch of tutorials aiming at introducting the basic tools for robotics control.
**Pinocchio** is coming with a large bunch of tutorials aiming at introducing the basic tools for robotics control.
The content of the tutorials are described [here](http://projects.laas.fr/gepetto/index.php/Teach/Supaero2018) and the source code of these tutorials is located [here](https://github.com/stack-of-tasks/pinocchio-tutorials).
## Dependencies
...
...
@@ -47,7 +47,7 @@ The content of the tutorials are described [here](http://projects.laas.fr/gepett
@@ -96,4 +96,4 @@ If you have taken part to the development of **Pinocchio**, feel free to add you
## Acknowledgments
The development of **Pinocchio** is supported by the [Gepetto team](http://projects.laas.fr/gepetto/) @LAAS-CNRS.
The development of **Pinocchio** is supported by the [Gepetto team](http://projects.laas.fr/gepetto/)[@LAAS-CNRS](http://www.laas.fr) and the [Willow team](https://www.di.ens.fr/willow/)[@INRIA](http://www.inria.fr).
bp::args("Model, the model of the kinematic tree",
"Data, the data associated to the model where the results are stored",
"Frame ID, the index of the frame.",
"Reference frame rf (either ReferenceFrame.LOCAL or ReferenceFrame.WORLD)"),
"Returns the Jacobian time variation of a specific frame (specified by Frame ID) expressed either in the world or the local frame."
"You have to call computeJointJacobiansTimeVariation and framesKinematics first."
"If rf is set to LOCAL, it returns the jacobian time variation associated to the frame index. Otherwise, it returns the jacobian time variation of the frame coinciding with the world frame.");
"Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame.\n"
...
...
@@ -94,7 +94,7 @@ namespace se3
"update_kinematics (true = update the value of the total jacobian)"),
"Computes the jacobian of a given given joint according to the given input configuration."
"If rf is set to LOCAL, it returns the jacobian associated to the joint frame. Otherwise, it returns the jacobian of the frame coinciding with the world frame.");
bp::def("getJointJacobian",get_jacobian_proxy,
bp::args("Model, the model of the kinematic tree",
"Data, the data associated to the model where the results are stored",
...
...
@@ -116,7 +116,7 @@ namespace se3
"Data, the data associated to the model where the results are stored",
"Joint ID, the index of the joint.",
"Reference frame rf (either ReferenceFrame.LOCAL or ReferenceFrame.WORLD)"),
"Computes the Jacobian time variation of a specific joint frame expressed either in the world frame or in the local frame of the joint."
"Computes the Jacobian time variation of a specific joint expressed either in the world frame or in the local frame of the joint."
"You have to call computeJointJacobiansTimeVariation first."
"If rf is set to LOCAL, it returns the jacobian time variation associated to the joint frame. Otherwise, it returns the jacobian time variation of the frame coinciding with the world frame.");
@@ -21,7 +21,15 @@ from __future__ import print_function
from.importlibpinocchio_pywrapasse3
from.deprecationimportdeprecated
@deprecated("This function has been renamed computeJointJacobians and will be removed in release 1.4.0 of Pinocchio. Please change for new computeJacobians.")
@deprecated("This function has been renamed updateFramePlacements when taking two arguments, and framesForwardKinematics when taking three. Please change your code to the appropriate method.")
defframesKinematics(model,data,q=None):
ifqisNone:
se3.updateFramePlacements(model,data)
else:
se3.framesForwardKinematics(model,data,q)
@deprecated("This function has been renamed computeJointJacobians and will be removed in release 1.4.0 of Pinocchio. Please change for new computeJointJacobians.")
@deprecated("This function has been renamed computeJacobiansTimeVariation and will be removed in release 1.4.0 of Pinocchio. Please change for new computeJacobiansTimeVariation.")
@deprecated("This function has been renamed computeJacobiansTimeVariation and will be removed in release 1.4.0 of Pinocchio. Please change for new computeJointJacobiansTimeVariation.")
* @brief Returns the jacobian of the frame expresssed either expressed in the LOCAL frame coordinate system or in the WORLD coordinate system,
* @brief Returns the spatial velocity of the frame expressed in the LOCAL frame coordinate system.
* You must first call se3::forwardKinematics to update placement and velocity values in data structure.
*
* @param[in] model The kinematic model
* @param[in] data Data associated to model
* @param[in] frame_id Id of the operational Frame
* @param[out] frame_v The spatial velocity of the Frame expressed in the coordinates Frame.
*
* @warning Fist or second order forwardKinematics should have been called first
*/
inlinevoidgetFrameVelocity(constModel&model,
constData&data,
constModel::FrameIndexframe_id,
Motion&frame_v);
/**
* @brief Returns the spatial acceleration of the frame expressed in the LOCAL frame coordinate system.
* You must first call se3::forwardKinematics to update placement values in data structure.
*
* @param[in] model The kinematic model
* @param[in] data Data associated to model
* @param[in] frame_id Id of the operational Frame
* @param[out] frame_a The spatial acceleration of the Frame expressed in the coordinates Frame.
*
* @warning Second order forwardKinematics should have been called first
*/
inlinevoidgetFrameAcceleration(constModel&model,
constData&data,
constModel::FrameIndexframe_id,
Motion&frame_a);
/**
* @brief Returns the jacobian of the frame expressed either in the LOCAL frame coordinate system or in the WORLD coordinate system,
* depending on the value of the template parameter rf.
* You must first call se3::computeJointJacobians followed by se3::framesForwardKinematics to update placement values in data structure.
*
* @tparam rf Reference frame in which the columns of the Jacobian are expressed.
*
* @remark Similarly to se3::getJointJacobian with LOCAL or WORLD templated parameters, if rf == LOCAL, this function returns the Jacobian of the frame expressed
* in the local coordinates of the frame, or if rl == WORDL, it returns the Jacobian expressed of the point coincident with the origin
* in the local coordinates of the frame, or if rl == WORLD, it returns the Jacobian expressed of the point coincident with the origin
* and expressed in a coordinate system aligned with the WORLD.
*
* @param[in] model The kinematic model
...
...
@@ -63,7 +125,7 @@ namespace se3
* @param[in] frame_id Id of the operational Frame
* @param[out] J The Jacobian of the Frame expressed in the coordinates Frame.
*
* @warning The function se3::computeJointJacobians and se3::framesForwardKinematics should have been called first.
* @warning The functions se3::computeJointJacobians and se3::framesForwardKinematics should have been called first.
*/
template<ReferenceFramerf>
voidgetFrameJacobian(constModel&model,
...
...
@@ -74,6 +136,7 @@ namespace se3
/**
* @brief Returns the jacobian of the frame expresssed the LOCAL frame coordinate system.
* You must first call se3::computeJointJacobians followed by se3::framesForwardKinematics to update placement values in data structure.
\deprecated This function is now deprecated. Please call se3::getFrameJacobian<ReferenceFrame> for same functionality
*
* @param[in] model The kinematic model
* @param[in] data Data associated to model
...
...
@@ -82,11 +145,30 @@ namespace se3
*
* @warning The function se3::computeJointJacobians and se3::framesForwardKinematics should have been called first.