expose-frames.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
7 
8 namespace pinocchio
9 {
10  namespace python
11  {
12 
14  const context::Model & model,
17  ReferenceFrame rf = LOCAL)
18  {
20  J.setZero();
22 
23  return J;
24  }
25 
27  const context::Model & model,
30  const context::SE3 & placement,
31  ReferenceFrame rf = LOCAL)
32  {
34  J.setZero();
36  return J;
37  }
38 
40  const context::Model & model,
43  ReferenceFrame rf = LOCAL)
44  {
45  return getFrameVelocity(model, data, frame_id, rf);
46  }
47 
49  const context::Model & model,
52  const context::SE3 & placement,
53  ReferenceFrame rf = LOCAL)
54  {
56  }
57 
59  const context::Model & model,
62  ReferenceFrame rf = LOCAL)
63  {
65  }
66 
68  const context::Model & model,
71  const context::SE3 & placement,
72  ReferenceFrame rf = LOCAL)
73  {
75  }
76 
78  const context::Model & model,
81  ReferenceFrame rf = LOCAL)
82  {
84  }
85 
87  const context::Model & model,
90  const context::SE3 & placement,
91  ReferenceFrame rf = LOCAL)
92  {
94  }
95 
97  const context::Model & model,
99  const context::VectorXs & q,
101  {
103  J.setZero();
105 
106  return J;
107  }
108 
110  const context::Model & model,
112  const context::VectorXs & q,
114  ReferenceFrame reference_frame)
115  {
117  J.setZero();
118  computeFrameJacobian(model, data, q, frame_id, reference_frame, J);
119 
120  return J;
121  }
122 
124  const context::Model & model,
127  ReferenceFrame rf)
128  {
129  context::Data::Matrix6x dJ(6, model.nv);
130  dJ.setZero();
131  getFrameJacobianTimeVariation(model, data, jointId, rf, dJ);
132 
133  return dJ;
134  }
135 
137  const context::Model & model,
139  const context::VectorXs & q,
140  const context::VectorXs & v,
142  const ReferenceFrame rf)
143  {
146 
148  }
149 
151  {
152  typedef context::Scalar Scalar;
153  typedef context::VectorXs VectorXs;
154  enum
155  {
157  };
158 
159  bp::def(
160  "updateFramePlacements", &updateFramePlacements<Scalar, Options, JointCollectionDefaultTpl>,
161  bp::args("model", "data"),
162  "Computes the placements of all the operational frames according to the current "
163  "joint placement stored in data"
164  "and puts the results in data.");
165 
166  bp::def(
167  "updateFramePlacement", &updateFramePlacement<Scalar, Options, JointCollectionDefaultTpl>,
168  bp::args("model", "data", "frame_id"),
169  "Computes the placement of the given operational frame (frame_id) according to the "
170  "current joint placement stored in data, stores the results in data and returns it.",
171  bp::return_value_policy<bp::return_by_value>());
172 
173  bp::def(
174  "getFrameVelocity", &get_frame_velocity_proxy1,
175  (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"),
176  bp::arg("reference_frame") = LOCAL),
177  "Returns the spatial velocity of the frame expressed in the coordinate system given "
178  "by reference_frame.\n"
179  "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint "
180  "spatial velocity stored in data.v");
181 
182  bp::def(
183  "getFrameVelocity", &get_frame_velocity_proxy2,
184  (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"),
185  bp::arg("reference_frame") = LOCAL),
186  "Returns the spatial velocity of the frame expressed in the coordinate system given "
187  "by reference_frame.\n"
188  "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint "
189  "spatial velocity stored in data.v");
190 
191  bp::def(
192  "getFrameAcceleration", &get_frame_acceleration_proxy1,
193  (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"),
194  bp::arg("reference_frame") = LOCAL),
195  "Returns the spatial acceleration of the frame expressed in the coordinate system "
196  "given by reference_frame.\n"
197  "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
198  "spatial acceleration stored in data.a .");
199 
200  bp::def(
201  "getFrameAcceleration", &get_frame_acceleration_proxy2,
202  (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"),
203  bp::arg("reference_frame") = LOCAL),
204  "Returns the spatial acceleration of the frame expressed in the coordinate system "
205  "given by reference_frame.\n"
206  "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
207  "spatial acceleration stored in data.a .");
208 
209  bp::def(
210  "getFrameClassicalAcceleration", &get_frame_classical_acceleration_proxy1,
211  (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"),
212  bp::arg("reference_frame") = LOCAL),
213  "Returns the \"classical\" acceleration of the frame expressed in the coordinate "
214  "system given by reference_frame.\n"
215  "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
216  "spatial acceleration stored in data.a .");
217 
218  bp::def(
219  "getFrameClassicalAcceleration", &get_frame_classical_acceleration_proxy2,
220  (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"),
221  bp::arg("reference_frame") = LOCAL),
222  "Returns the \"classical\" acceleration of the frame expressed in the coordinate "
223  "system given by reference_frame.\n"
224  "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
225  "spatial acceleration stored in data.a .");
226 
227  bp::def(
228  "framesForwardKinematics",
229  &framesForwardKinematics<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
230  bp::args("model", "data", "q"),
231  "Calls first the forwardKinematics(model,data,q) and then update the Frame placement "
232  "quantities (data.oMf).");
233 
234  bp::def(
235  "computeFrameJacobian",
237  const context::Model &, context::Data &, const context::VectorXs &,
239  bp::args("model", "data", "q", "frame_id", "reference_frame"),
240  "Computes the Jacobian of the frame given by its frame_id in the coordinate system "
241  "given by reference_frame.\n");
242 
243  bp::def(
244  "computeFrameJacobian",
246  const context::Model &, context::Data &, const context::VectorXs &,
248  bp::args("model", "data", "q", "frame_id"),
249  "Computes the Jacobian of the frame given by its frame_id.\n"
250  "The columns of the Jacobian are expressed in the coordinates system of the Frame itself.\n"
251  "In other words, the velocity of the frame vF expressed in the local coordinate is given "
252  "by J*v,"
253  "where v is the joint velocity.");
254 
255  bp::def(
256  "getFrameJacobian", &get_frame_jacobian_proxy1,
257  bp::args("model", "data", "frame_id", "reference_frame"),
258  "Computes the Jacobian of the frame given by its ID either in the LOCAL, "
259  "LOCAL_WORLD_ALIGNED or the WORLD coordinates systems.\n"
260  "In other words, the velocity of the frame vF expressed in the reference frame is "
261  "given by J*v,"
262  "where v is the joint velocity vector.\n"
263  "remarks: computeJointJacobians(model,data,q) must have been called first.");
264 
265  bp::def(
266  "getFrameJacobian", &get_frame_jacobian_proxy2,
267  bp::args("model", "data", "joint_id", "placement", "reference_frame"),
268  "Computes the Jacobian of the frame given by its placement with respect to the Joint "
269  "frame and expressed the solution either in the LOCAL, LOCAL_WORLD_ALIGNED or the "
270  "WORLD coordinates systems.\n"
271  "In other words, the velocity of the frame vF expressed in the reference frame is "
272  "given by J*v,"
273  "where v is the joint velocity vector.\n\n"
274  "remarks: computeJointJacobians(model,data,q) must have been called first.");
275 
276  bp::def(
277  "frameJacobianTimeVariation", &frame_jacobian_time_variation_proxy,
278  bp::args("model", "data", "q", "v", "frame_id", "reference_frame"),
279  "Computes the Jacobian Time Variation of the frame given by its frame_id either in "
280  "the reference frame provided by reference_frame.\n");
281 
282  bp::def(
283  "getFrameJacobianTimeVariation", get_frame_jacobian_time_variation_proxy,
284  bp::args("model", "data", "frame_id", "reference_frame"),
285  "Returns the Jacobian time variation of the frame given by its frame_id either in "
286  "the reference frame provided by reference_frame.\n"
287  "You have to call computeJointJacobiansTimeVariation(model,data,q,v) and "
288  "updateFramePlacements(model,data) first.");
289 
290  bp::def(
291  "computeSupportedInertiaByFrame",
292  &computeSupportedInertiaByFrame<double, 0, JointCollectionDefaultTpl>,
293  bp::args("model", "data", "frame_id", "with_subtree"),
294  "Computes the supported inertia by the frame (given by frame_id) and returns it.\n"
295  "The supported inertia corresponds to the sum of the inertias of all the child frames "
296  "(that belongs to the same joint body) and the child joints, if with_subtree=True.\n"
297  "You must first call pinocchio::forwardKinematics to update placement values in data "
298  "structure.");
299 
300  bp::def(
301  "computeSupportedForceByFrame",
302  &computeSupportedForceByFrame<double, 0, JointCollectionDefaultTpl>,
303  bp::args("model", "data", "frame_id"),
304  "Computes the supported force of the frame (given by frame_id) and returns it.\n"
305  "The supported force corresponds to the sum of all the forces experienced after the "
306  "given frame.\n"
307  "You must first call pinocchio::rnea to update placement values in data structure.");
308  }
309  } // namespace python
310 
311 } // namespace pinocchio
pinocchio::python::get_frame_jacobian_time_variation_proxy
static context::Data::Matrix6x get_frame_jacobian_time_variation_proxy(const context::Model &model, context::Data &data, context::Data::FrameIndex jointId, ReferenceFrame rf)
Definition: expose-frames.cpp:123
pinocchio::python::frame_jacobian_time_variation_proxy
static context::Data::Matrix6x frame_jacobian_time_variation_proxy(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::Data::FrameIndex frame_id, const ReferenceFrame rf)
Definition: expose-frames.cpp:136
frames.hpp
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::getFrameJacobian
void getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame,...
pinocchio::DataTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/data.hpp:63
pinocchio::python::get_frame_jacobian_proxy1
static context::Data::Matrix6x get_frame_jacobian_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:13
pinocchio::python::get_frame_acceleration_proxy2
static context::Data::Motion get_frame_acceleration_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:67
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::getFrameVelocity
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame....
pinocchio::python::get_frame_velocity_proxy1
static context::Data::Motion get_frame_velocity_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:39
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::getFrameClassicalAcceleration
MotionTpl< Scalar, Options > getFrameClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the Frame expressed in the desired reference frame....
pinocchio::DataTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/data.hpp:65
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
inverse-kinematics-3d.J
J
Definition: inverse-kinematics-3d.py:28
pinocchio::computeJointJacobiansTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
pinocchio::python::get_frame_jacobian_proxy2
static context::Data::Matrix6x get_frame_jacobian_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:26
pinocchio::python::VectorXs
context::VectorXs VectorXs
Definition: admm-solver.cpp:30
pinocchio::computeFrameJacobian
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::placement
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Definition: spatial/classic-acceleration.hpp:122
pinocchio::updateFramePlacements
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
algorithms.hpp
python
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::python::exposeFramesAlgo
void exposeFramesAlgo()
Definition: expose-frames.cpp:150
pinocchio::python::get_frame_classical_acceleration_proxy1
static context::Data::Motion get_frame_classical_acceleration_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:77
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
pinocchio::python::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
contact-cholesky.frame_id
frame_id
Definition: contact-cholesky.py:19
pinocchio::getFrameAcceleration
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame....
pinocchio::getFrameJacobianTimeVariation
void getFrameJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &dJ)
Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the ...
pinocchio::python::get_frame_velocity_proxy2
static context::Data::Motion get_frame_velocity_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:48
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:92
pinocchio::python::get_frame_classical_acceleration_proxy2
static context::Data::Motion get_frame_classical_acceleration_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:86
pinocchio::MotionTpl< Scalar, Options >
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:33
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::get_frame_acceleration_proxy1
static context::Data::Motion get_frame_acceleration_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
Definition: expose-frames.cpp:58
pinocchio::python::compute_frame_jacobian_proxy
static context::Data::Matrix6x compute_frame_jacobian_proxy(const context::Model &model, context::Data &data, const context::VectorXs &q, context::Data::FrameIndex frame_id)
Definition: expose-frames.cpp:96
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:43