GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/residuals/contact-wrench-cone-double.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 18 0.0%
Branches: 0 64 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2025, University of Edinburgh, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 // Auto-generated file for double
10 #include "crocoddyl/multibody/residuals/contact-wrench-cone.hpp"
11
12 #include "python/crocoddyl/multibody/multibody.hpp"
13 #include "python/crocoddyl/utils/deprecate.hpp"
14
15 namespace crocoddyl {
16 namespace python {
17
18 template <typename Model>
19 struct ResidualModelContactWrenchConeVisitor
20 : public bp::def_visitor<ResidualModelContactWrenchConeVisitor<Model>> {
21 typedef typename Model::ResidualDataAbstract Data;
22 typedef typename Model::StateMultibody State;
23 typedef typename Model::WrenchCone Cone;
24 typedef typename Model::VectorXs VectorXs;
25 template <class PyClass>
26 void visit(PyClass& cl) const {
27 cl.def(bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Cone>(
28 bp::args("self", "state", "id", "fref"),
29 "Initialize the contact wrench cone residual model.\n\n"
30 "The default nu is obtained from state.nv. Note that this "
31 "constructor can be used for forward-dynamics cases only.\n"
32 ":param state: state of the multibody system\n"
33 ":param id: reference frame id\n"
34 ":param fref: contact wrench cone"))
35 .def(
36 "calc",
37 static_cast<void (Model::*)(
38 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
39 const Eigen::Ref<const VectorXs>&)>(&Model::calc),
40 "Compute the contact wrench cone residual.\n\n"
41 ":param data: residual data\n"
42 ":param x: state point (dim. state.nx)\n"
43 ":param u: control input (dim. nu)")
44 .def("calc",
45 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
46 const Eigen::Ref<const VectorXs>&)>(
47 &Model::calc),
48 bp::args("self", "data", "x"))
49 .def(
50 "calcDiff",
51 static_cast<void (Model::*)(
52 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
53 const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff),
54 bp::args("self", "data", "x", "u"),
55 "Compute the Jacobians of the contact wrench cone residual.\n\n"
56 "It assumes that calc has been run first.\n"
57 ":param data: action data\n"
58 ":param x: state point (dim. state.nx)\n"
59 ":param u: control input (dim. nu)")
60 .def("calcDiff",
61 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
62 const Eigen::Ref<const VectorXs>&)>(
63 &Model::calcDiff),
64 bp::args("self", "data", "x"))
65 .def(
66 "createData", &Model::createData,
67 bp::with_custodian_and_ward_postcall<0, 2>(),
68 bp::args("self", "data"),
69 "Create the contact wrench cone residual data.\n\n"
70 "Each residual model has its own data that needs to be allocated. "
71 "This function\n"
72 "returns the allocated data for the contact wrench cone residual.\n"
73 ":param data: shared data\n"
74 ":return residual data.")
75 .add_property(
76 "id", bp::make_function(&Model::get_id),
77 bp::make_function(&Model::set_id,
78 deprecated<>("Deprecated. Do not use set_id, "
79 "instead create a new model")),
80 "reference frame id")
81 .add_property("reference",
82 bp::make_function(&Model::get_reference,
83 bp::return_internal_reference<>()),
84 &Model::set_reference, "reference contact wrench cone");
85 }
86 };
87
88 template <typename Data>
89 struct ResidualDataContactWrenchConeVisitor
90 : public bp::def_visitor<ResidualDataContactWrenchConeVisitor<Data>> {
91 template <class PyClass>
92 void visit(PyClass& cl) const {
93 cl.add_property(
94 "contact",
95 bp::make_getter(&Data::contact,
96 bp::return_value_policy<bp::return_by_value>()),
97 bp::make_setter(&Data::contact),
98 "contact data associated with the current residual");
99 }
100 };
101
102 #define CROCODDYL_RESIDUAL_MODEL_CONTACT_WRENCH_CONE_PYTHON_BINDINGS(Scalar) \
103 typedef ResidualModelContactWrenchConeTpl<Scalar> Model; \
104 typedef ResidualModelAbstractTpl<Scalar> ModelBase; \
105 typedef typename Model::StateMultibody State; \
106 typedef typename Model::WrenchCone Cone; \
107 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
108 bp::class_<Model, bp::bases<ModelBase>>( \
109 "ResidualModelContactWrenchCone", \
110 bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Cone, \
111 std::size_t, bp::optional<bool>>( \
112 bp::args("self", "state", "id", "fref", "nu", "fwddyn"), \
113 "Initialize the contact wrench cone residual model.\n\n" \
114 ":param state: state of the multibody system\n" \
115 ":param id: reference frame id\n" \
116 ":param fref: contact wrench cone\n" \
117 ":param nu: dimension of control vector\n" \
118 ":param fwddyn: indicate if we have a forward dynamics problem " \
119 "(True) or inverse dynamics problem (False) (default True)")) \
120 .def(ResidualModelContactWrenchConeVisitor<Model>()) \
121 .def(CastVisitor<Model>()) \
122 .def(PrintableVisitor<Model>()) \
123 .def(CopyableVisitor<Model>());
124
125 #define CROCODDYL_RESIDUAL_DATA_CONTACT_WRENCH_CONE_PYTHON_BINDINGS(Scalar) \
126 typedef ResidualDataContactWrenchConeTpl<Scalar> Data; \
127 typedef ResidualDataAbstractTpl<Scalar> DataBase; \
128 typedef ResidualModelContactWrenchConeTpl<Scalar> Model; \
129 typedef Model::DataCollectorAbstract DataCollector; \
130 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
131 bp::class_<Data, bp::bases<DataBase>>( \
132 "ResidualDataContactWrenchCone", \
133 "Data for contact wrench cone residual.\n\n", \
134 bp::init<Model*, DataCollector*>( \
135 bp::args("self", "model", "data"), \
136 "Create contact wrench cone residual data.\n\n" \
137 ":param model: contact wrench cone residual model\n" \
138 ":param data: shared data")[bp::with_custodian_and_ward< \
139 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \
140 .def(ResidualDataContactWrenchConeVisitor<Data>()) \
141 .def(CopyableVisitor<Data>());
142
143 void exposeResidualContactWrenchCone() {
144 CROCODDYL_RESIDUAL_MODEL_CONTACT_WRENCH_CONE_PYTHON_BINDINGS(double)
145 CROCODDYL_RESIDUAL_DATA_CONTACT_WRENCH_CONE_PYTHON_BINDINGS(double)
146 }
147
148 } // namespace python
149 } // namespace crocoddyl
150