6
6
// All rights reserved.
7
7
// /////////////////////////////////////////////////////////////////////////////
8
8
9
- #include " crocoddyl/multibody/actuations/floating-base-propellers.hpp"
10
-
9
+ #include " crocoddyl/multibody/actuations/floating-base-thrusters.hpp"
11
10
#include " python/crocoddyl/multibody/multibody.hpp"
12
11
#include " python/crocoddyl/utils/copyable.hpp"
13
12
#include " python/crocoddyl/utils/printable.hpp"
@@ -17,84 +16,83 @@ namespace crocoddyl {
17
16
18
17
namespace python {
19
18
20
- void exposeActuationFloatingBasePropeller () {
21
- bp::enum_<PropellerType >(" PropellerType " )
19
+ void exposeActuationFloatingBaseThruster () {
20
+ bp::enum_<ThrusterType >(" ThrusterType " )
22
21
.value (" CW" , CW)
23
22
.value (" CCW" , CCW)
24
23
.export_values ();
25
24
26
- bp::class_<Propeller>(
27
- " Propeller" , " Model for propellers" ,
28
- bp::init<pinocchio::SE3, double , double , bp::optional<PropellerType>>(
29
- bp::args (" self" , " M" , " cthrust" , " ctau" , " type" ),
30
- " Initialize the propeller in a give pose from the root joint.\n\n "
25
+ bp::class_<Thruster>(
26
+ " Thruster" , " Model for thrusters" ,
27
+ bp::init<pinocchio::SE3, double ,
28
+ bp::optional<ThrusterType, double , double >>(
29
+ bp::args (" self" , " M" , " ctorque" , " type" , " min_thrust" , " max_thrust" ),
30
+ " Initialize the thruster in a give pose from the root joint.\n\n "
31
31
" :param M: pose from root joint\n "
32
- " :param cthrust: coefficient of thrust (it relates propeller's "
33
- " (square) velocity to its thrust)\n "
34
- " :param ctau: coefficient of torque (it relates propeller's (square) "
35
- " velocity to its torque)\n "
36
- " :param type: type of propeller (clockwise or counterclockwise, "
37
- " default clockwise)" ))
38
- .def (bp::init<double , double , bp::optional<PropellerType>>(
39
- bp::args (" self" , " cthrust" , " ctau" , " type" ),
40
- " Initialize the propeller in a pose in the origin of the root "
41
- " joint.\n\n "
42
- " :param cthrust: coefficient of thrust (it relates propeller's "
43
- " (square) velocity to its thrust)\n "
44
- " :param ctau: coefficient of torque (it relates propeller's (square) "
45
- " velocity to its torque)\n "
46
- " :param type: type of propeller (clockwise or counterclockwise, "
47
- " default clockwise)" ))
48
- .def_readwrite (" pose" , &Propeller::pose,
49
- " propeller pose (traslation, rotation)" )
50
- .def_readwrite (" cthrust" , &Propeller::cthrust, " coefficient of thrust" )
51
- .def_readwrite (" ctorque" , &Propeller::ctorque, " coefficient of torque" )
52
- .def_readwrite (" type" , &Propeller::type,
53
- " type of propeller (clockwise or counterclockwise)" )
54
- .def (PrintableVisitor<Propeller>())
55
- .def (CopyableVisitor<Propeller>());
32
+ " :param ctorque: coefficient of generated torque per thrust\n "
33
+ " :param type: type of thruster (clockwise or counterclockwise, "
34
+ " default clockwise)\n "
35
+ " :param min_thrust: minimum thrust (default 0.)\n "
36
+ " :param max_thrust: maximum thrust (default np.inf)" ))
37
+ .def (bp::init<double , bp::optional<ThrusterType, double , double >>(
38
+ bp::args (" self" , " ctorque" , " type" , " min_thrust" , " max_thrust" ),
39
+ " Initialize the thruster in a give pose from the root joint.\n\n "
40
+ " :param ctorque: coefficient of generated torque per thrust\n "
41
+ " :param type: type of thruster (clockwise or counterclockwise, "
42
+ " default clockwise)\n "
43
+ " :param min_thrust: minimum thrust (default 0.)\n "
44
+ " :param max_thrust: maximum thrust (default np.inf)" ))
45
+ .def_readwrite (" pose" , &Thruster::pose,
46
+ " thruster pose (traslation, rotation)" )
47
+ .def_readwrite (" ctorque" , &Thruster::ctorque,
48
+ " coefficient of generated torque per thrust" )
49
+ .def_readwrite (" type" , &Thruster::type,
50
+ " type of thruster (clockwise or counterclockwise)" )
51
+ .def_readwrite (" min_thrust" , &Thruster::min_thrust, " minimum thrust" )
52
+ .def_readwrite (" max_thrust" , &Thruster::min_thrust, " maximum thrust" )
53
+ .def (PrintableVisitor<Thruster>())
54
+ .def (CopyableVisitor<Thruster>());
56
55
57
- StdVectorPythonVisitor<std::vector<Propeller >, true >::expose (
58
- " StdVec_Propeller " );
56
+ StdVectorPythonVisitor<std::vector<Thruster >, true >::expose (
57
+ " StdVec_Thruster " );
59
58
60
59
bp::register_ptr_to_python<
61
- boost::shared_ptr<crocoddyl::ActuationModelFloatingBasePropellers >>();
60
+ boost::shared_ptr<crocoddyl::ActuationModelFloatingBaseThrusters >>();
62
61
63
- bp::class_<ActuationModelFloatingBasePropellers ,
62
+ bp::class_<ActuationModelFloatingBaseThrusters ,
64
63
bp::bases<ActuationModelAbstract>>(
65
- " ActuationModelFloatingBasePropellers " ,
66
- " Actuation models for floating base systems actuated with propellers "
64
+ " ActuationModelFloatingBaseThrusters " ,
65
+ " Actuation models for floating base systems actuated with thrusters "
67
66
" (e.g. aerial "
68
67
" manipulators)." ,
69
- bp::init<boost::shared_ptr<StateMultibody>, std::vector<Propeller >>(
70
- bp::args (" self" , " state" , " propellers " ),
68
+ bp::init<boost::shared_ptr<StateMultibody>, std::vector<Thruster >>(
69
+ bp::args (" self" , " state" , " thrusters " ),
71
70
" Initialize the floating base actuation model equipped with "
72
- " propellers .\n\n "
71
+ " thrusters .\n\n "
73
72
" :param state: state of multibody system\n "
74
- " :param propellers : vector of propellers " ))
75
- .def <void (ActuationModelFloatingBasePropellers ::*)(
73
+ " :param thrusters : vector of thrusters " ))
74
+ .def <void (ActuationModelFloatingBaseThrusters ::*)(
76
75
const boost::shared_ptr<ActuationDataAbstract>&,
77
76
const Eigen::Ref<const Eigen::VectorXd>&,
78
77
const Eigen::Ref<const Eigen::VectorXd>&)>(
79
- " calc" , &ActuationModelFloatingBasePropellers ::calc,
78
+ " calc" , &ActuationModelFloatingBaseThrusters ::calc,
80
79
bp::args (" self" , " data" , " x" , " u" ),
81
80
" Compute the actuation signal and actuation set from the thrust\n "
82
81
" forces and joint torque inputs u.\n\n "
83
- " :param data: floating base propellers actuation data\n "
82
+ " :param data: floating base thrusters actuation data\n "
84
83
" :param x: state point (dim. state.nx)\n "
85
84
" :param u: joint torque input (dim. nu)" )
86
- .def (
87
- " calcDiff" , &ActuationModelFloatingBasePropellers::calcDiff,
88
- bp::args (" self" , " data" , " x" , " u" ),
89
- " Compute the derivatives of the actuation model.\n\n "
90
- " It computes the partial derivatives of the propeller actuation. It\n "
91
- " assumes that calc has been run first. The reason is that the\n "
92
- " derivatives are constant and defined in createData. The Hessian\n "
93
- " is constant, so we don't write again this value.\n "
94
- " :param data: floating base propellers actuation data\n "
95
- " :param x: state point (dim. state.nx)\n "
96
- " :param u: joint torque input (dim. nu)" )
97
- .def (" commands" , &ActuationModelFloatingBasePropellers::commands,
85
+ .def (" calcDiff" , &ActuationModelFloatingBaseThrusters::calcDiff,
86
+ bp::args (" self" , " data" , " x" , " u" ),
87
+ " Compute the derivatives of the actuation model.\n\n "
88
+ " It computes the partial derivatives of the thruster actuation. It\n "
89
+ " assumes that calc has been run first. The reason is that the\n "
90
+ " derivatives are constant and defined in createData. The Hessian\n "
91
+ " is constant, so we don't write again this value.\n "
92
+ " :param data: floating base thrusters actuation data\n "
93
+ " :param x: state point (dim. state.nx)\n "
94
+ " :param u: joint torque input (dim. nu)" )
95
+ .def (" commands" , &ActuationModelFloatingBaseThrusters::commands,
98
96
bp::args (" self" , " data" , " x" , " tau" ),
99
97
" Compute the thrust and joint torque commands from the generalized "
100
98
" torques.\n\n "
@@ -103,40 +101,40 @@ void exposeActuationFloatingBasePropeller() {
103
101
" :param x: state point (dim. state.nx)\n "
104
102
" :param tau: generalized torques (dim state.nv)" )
105
103
.def (" torqueTransform" ,
106
- &ActuationModelFloatingBasePropellers ::torqueTransform,
104
+ &ActuationModelFloatingBaseThrusters ::torqueTransform,
107
105
bp::args (" self" , " data" , " x" , " tau" ),
108
106
" Compute the torque transform from generalized torques to thrust "
109
107
" and joint torque inputs.\n\n "
110
108
" It stores the results in data.Mtau.\n "
111
- " :param data: floating base propellers actuation data\n "
109
+ " :param data: floating base thrusters actuation data\n "
112
110
" :param x: state point (dim. state.nx)\n "
113
111
" :param tau: generalized torques (dim state.nv)" )
114
- .def (" createData" , &ActuationModelFloatingBasePropellers ::createData,
112
+ .def (" createData" , &ActuationModelFloatingBaseThrusters ::createData,
115
113
bp::args (" self" ),
116
- " Create the floating base propellers actuation data." )
117
- .add_property (" propellers " ,
118
- bp::make_function (
119
- &ActuationModelFloatingBasePropellers::get_propellers ,
120
- bp::return_value_policy<bp::return_by_value>()),
121
- bp::make_function (
122
- &ActuationModelFloatingBasePropellers::set_propellers ),
123
- " vector of propellers " )
124
- .add_property (" npropellers " ,
114
+ " Create the floating base thrusters actuation data." )
115
+ .add_property (
116
+ " thrusters " ,
117
+ bp::make_function (&ActuationModelFloatingBaseThrusters::get_thrusters ,
118
+ bp::return_value_policy<bp::return_by_value>()),
119
+ bp::make_function (
120
+ &ActuationModelFloatingBaseThrusters::set_thrusters ),
121
+ " vector of thrusters " )
122
+ .add_property (" nthrusters " ,
125
123
bp::make_function (
126
- &ActuationModelFloatingBasePropellers::get_npropellers ),
127
- " number of propellers " )
124
+ &ActuationModelFloatingBaseThrusters::get_nthrusters ),
125
+ " number of thrusters " )
128
126
.add_property (
129
127
" Wthrust" ,
130
- bp::make_function (&ActuationModelFloatingBasePropellers ::get_Wthrust,
128
+ bp::make_function (&ActuationModelFloatingBaseThrusters ::get_Wthrust,
131
129
bp::return_value_policy<bp::return_by_value>()),
132
- " matrix mapping from thrusts to propeller wrenches" )
130
+ " matrix mapping from thrusts to thruster wrenches" )
133
131
.add_property (
134
132
" S" ,
135
- bp::make_function (&ActuationModelFloatingBasePropellers ::get_S,
133
+ bp::make_function (&ActuationModelFloatingBaseThrusters ::get_S,
136
134
bp::return_value_policy<bp::return_by_value>()),
137
135
" selection matrix for under-actuation part" )
138
- .def (PrintableVisitor<ActuationModelFloatingBasePropellers >())
139
- .def (CopyableVisitor<ActuationModelFloatingBasePropellers >());
136
+ .def (PrintableVisitor<ActuationModelFloatingBaseThrusters >())
137
+ .def (CopyableVisitor<ActuationModelFloatingBaseThrusters >());
140
138
}
141
139
142
140
} // namespace python
0 commit comments