Skip to content

Commit

Permalink
WIP: Correct use of "associated to"
Browse files Browse the repository at this point in the history
  • Loading branch information
stephane-caron committed Mar 14, 2024
1 parent 30a52cd commit d7a60cb
Show file tree
Hide file tree
Showing 10 changed files with 18 additions and 18 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ ENDIF()
OPTION(BUILD_BENCHMARK "Build the benchmarks" OFF)
OPTION(BUILD_UTILS "Build the utils" OFF)
OPTION(BUILD_PYTHON_INTERFACE "Build the Python bindings" ON)
option(GENERATE_PYTHON_STUBS "Generate the Python stubs associated to the Python library" OFF)
option(GENERATE_PYTHON_STUBS "Generate the Python stubs associated with the Python library" OFF)
OPTION(BUILD_WITH_COMMIT_VERSION "Build libraries by setting specific commit version" OFF)

IF(DEFINED BUILD_UNIT_TESTS)
Expand Down
4 changes: 2 additions & 2 deletions bindings/python/algorithm/expose-jacobian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ namespace pinocchio
"Computes the jacobian of a given given joint according to the given entries in data.\n"
"If reference_frame is set to LOCAL, it returns the Jacobian expressed in the local coordinate system of the joint.\n"
"If reference_frame is set to LOCAL_WORLD_ALIGNED, it returns the Jacobian expressed in the coordinate system of the frame centered on the joint, but aligned with the WORLD axes.\n"
"If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame associated to the WORLD.\n\n"
"If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame corresponding to the WORLD.\n\n"
"Parameters:\n"
"\tmodel: model of the kinematic tree\n"
"\tdata: data related to the model\n"
Expand All @@ -109,7 +109,7 @@ namespace pinocchio
"You have to call computeJointJacobiansTimeVariation first. This function also computes the full model Jacobian contained in data.J.\n"
"If reference_frame is set to LOCAL, it returns the Jacobian expressed in the local coordinate system of the joint.\n"
"If reference_frame is set to LOCAL_WORLD_ALIGNED, it returns the Jacobian expressed in the coordinate system of the frame centered on the joint, but aligned with the WORLD axes.\n"
"If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame associated to the WORLD.\n\n"
"If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame corresponding to the WORLD.\n\n"
"Parameters:\n"
"\tmodel: model of the kinematic tree\n"
"\tdata: data related to the model\n"
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/algorithm/expose-joints.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ namespace pinocchio
bp::def("neutral",
&neutral<double,0,JointCollectionDefaultTpl>,
bp::arg("model"),
"Returns the neutral configuration vector associated to the model.\n\n"
"Returns the neutral configuration vector corresponding to the model.\n\n"
"Parameters:\n"
"\tmodel: model of the kinematic tree\n");

Expand Down
4 changes: 2 additions & 2 deletions doc/a-features/intro.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ Python.

Within a model, a robot is represented as a kinematic tree, containing a
collection of all the joints, information about their connectivity, and,
optionally, the inertial quantities associated to each link. In
optionally, the inertial quantities corresponding to each link. In
Pinocchio a joint can have one or several degrees of freedom, and it
belongs to one of the following categories:
- **Revolute** joints, rotating around a fixed axis, either one of \f$X,Y,Z\f$ or a custom one;
Expand Down Expand Up @@ -85,7 +85,7 @@ operators.

Aside the kinematic model, Pinocchio defines a geometric model, i.e. the
volumes attached to the kinematic tree. This model can be used for
displaying the robot and computing quantities associated to collisions.
displaying the robot and computing quantities for collisions.
Like the kinematic model, the fixed quantities (placement and shape of
the volumes) are stored in a *GeometricModel* object, while buffers and
quantities used by associated algorithms are defined in a object. The
Expand Down
2 changes: 1 addition & 1 deletion doc/d-practical-exercises/1-directgeom.md
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ You can access the visual object composing the robot model by

```py
visualObj = robot.visual_model.geometryObjects[4] # 3D object representing the robot forarm
visualName = visualObj.name # Name associated to this object
visualName = visualObj.name # Name corresponding to this object
visualRef = robot.getViewerNodeName(visualObj, pin.GeometryType.VISUAL) # Viewer reference (string) representing this object
```

Expand Down
2 changes: 1 addition & 1 deletion doc/d-practical-exercises/src/graph.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
class Graph(object):
def __init__(self):
self.children = {} # dictionnary giving the list of childrens for each node.
self.q = [] # configuration associated to each node.
self.q = [] # configuration associated with each node.
self.connex = [] # ID of the connex component the node is belonging to.
self.nconnex = 0 # number of connex components.
self.existing_connex = [] # List of existing connex component ID.
Expand Down
6 changes: 3 additions & 3 deletions examples/collisions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,18 +25,18 @@ int main(int /*argc*/, char ** /*argv*/)
Model model;
pinocchio::urdf::buildModel(urdf_filename,model);

// Build the data associated to the model
// Build the data corresponding to the model
Data data(model);

// Load the geometries associated to model which are contained in the URDF file
// Load the geometries associated with model which are contained in the URDF file
GeometryModel geom_model;
pinocchio::urdf::buildGeom(model, urdf_filename, pinocchio::COLLISION, geom_model, robots_model_path);

// Add all possible collision pairs and remove the ones collected in the SRDF file
geom_model.addAllCollisionPairs();
pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename);

// Build the data associated to the geom_model
// Build the data associated with the geometry model
GeometryData geom_data(geom_model); // contained the intermediate computations, like the placement of all the geometries with respect to the world frame

// Load the reference configuration of the robots (this one should be collision free)
Expand Down
4 changes: 2 additions & 2 deletions include/pinocchio/algorithm/kinematics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,8 @@ namespace pinocchio
* @brief Returns the spatial velocity of the joint expressed in the desired reference frame.
* You must first call pinocchio::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] model Kinematic model
* @param[in] data Data associated with the model
* @param[in] jointId Id of the joint
* @param[in] rf Reference frame in which the velocity is expressed.
*
Expand Down
4 changes: 2 additions & 2 deletions include/pinocchio/multibody/data.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ namespace pinocchio
/// \brief The type of Tensor for Kinematics and Dynamics second order derivatives
typedef Tensor<Scalar,3,Options> Tensor3x;

/// \brief Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,
/// \brief Vector of pinocchio::JointData corresponding to the pinocchio::JointModel stored in model,
/// encapsulated in JointDataAccessor.
JointDataVector joints;

Expand Down Expand Up @@ -131,7 +131,7 @@ namespace pinocchio

/// \brief Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects.
/// \note In the multibody dynamics equation \f$ M\ddot{q} + b(q, \dot{q}) = \tau \f$,
/// the non linear effects are associated to the term \f$b\f$.
/// the non linear effects correspond to the term \f$b\f$.
VectorXs nle;

/// \brief Vector of generalized gravity (dim model.nv).
Expand Down
6 changes: 3 additions & 3 deletions include/pinocchio/parsers/srdf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace pinocchio
const bool verbose = false);

///
/// \brief Get the reference configurations of a given model associated to a SRDF file.
/// \brief Get the reference configurations of a given model loaded from an SRDF file.
/// It throws if the SRDF file is incorrect. The reference configurations are
/// saved in a map indexed by the configuration name (model.referenceConfigurations).
///
Expand All @@ -58,7 +58,7 @@ namespace pinocchio
const bool verbose = false);

///
/// \brief Get the reference configurations of a given model associated to a SRDF file.
/// \brief Get the reference configurations of a given model loaded from an SRDF file.
/// It throws if the SRDF file is incorrect. The reference configurations are
/// saved in a map indexed by the configuration name (model.referenceConfigurations).
///
Expand All @@ -73,7 +73,7 @@ namespace pinocchio
const bool verbose = false);

///
/// \brief Load the rotor params of a given model associated to a SRDF file.
/// \brief Load the rotor params of a given model loaded from an SRDF file.
/// It throws if the SRDF file is incorrect.
///
/// \param[in] model The Model for which we want the rotor parmeters
Expand Down

0 comments on commit d7a60cb

Please sign in to comment.