Skip to content

Commit

Permalink
[actuation] Changed notion of propellers to thrusters
Browse files Browse the repository at this point in the history
  • Loading branch information
cmastalli committed Jan 24, 2024
1 parent 89ec337 commit fd0787e
Show file tree
Hide file tree
Showing 16 changed files with 255 additions and 274 deletions.
2 changes: 1 addition & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).

## [Unreleased]

* Introduced floating base propeller actuation model in https://github.com/loco-3d/crocoddyl/pull/1213
* Introduced floating base thruster actuation model in https://github.com/loco-3d/crocoddyl/pull/1213
* Fixed quadruped and biped examples in https://github.com/loco-3d/crocoddyl/pull/1208
* Fixed terminal computation in Python models in https://github.com/loco-3d/crocoddyl/pull/1204
* Fixed handling of unbounded values for `ActivationBounds` in https://github.com/loco-3d/crocoddyl/pull/1191
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,7 @@
// All rights reserved.
///////////////////////////////////////////////////////////////////////////////

#include "crocoddyl/multibody/actuations/floating-base-propellers.hpp"

#include "crocoddyl/multibody/actuations/floating-base-thrusters.hpp"
#include "python/crocoddyl/multibody/multibody.hpp"
#include "python/crocoddyl/utils/copyable.hpp"
#include "python/crocoddyl/utils/printable.hpp"
Expand All @@ -17,84 +16,83 @@ namespace crocoddyl {

namespace python {

void exposeActuationFloatingBasePropeller() {
bp::enum_<PropellerType>("PropellerType")
void exposeActuationFloatingBaseThruster() {
bp::enum_<ThrusterType>("ThrusterType")
.value("CW", CW)
.value("CCW", CCW)
.export_values();

bp::class_<Propeller>(
"Propeller", "Model for propellers",
bp::init<pinocchio::SE3, double, double, bp::optional<PropellerType>>(
bp::args("self", "M", "cthrust", "ctau", "type"),
"Initialize the propeller in a give pose from the root joint.\n\n"
bp::class_<Thruster>(
"Thruster", "Model for thrusters",
bp::init<pinocchio::SE3, double,
bp::optional<ThrusterType, double, double>>(
bp::args("self", "M", "ctorque", "type", "min_thrust", "max_thrust"),
"Initialize the thruster in a give pose from the root joint.\n\n"
":param M: pose from root joint\n"
":param cthrust: coefficient of thrust (it relates propeller's "
"(square) velocity to its thrust)\n"
":param ctau: coefficient of torque (it relates propeller's (square) "
"velocity to its torque)\n"
":param type: type of propeller (clockwise or counterclockwise, "
"default clockwise)"))
.def(bp::init<double, double, bp::optional<PropellerType>>(
bp::args("self", "cthrust", "ctau", "type"),
"Initialize the propeller in a pose in the origin of the root "
"joint.\n\n"
":param cthrust: coefficient of thrust (it relates propeller's "
"(square) velocity to its thrust)\n"
":param ctau: coefficient of torque (it relates propeller's (square) "
"velocity to its torque)\n"
":param type: type of propeller (clockwise or counterclockwise, "
"default clockwise)"))
.def_readwrite("pose", &Propeller::pose,
"propeller pose (traslation, rotation)")
.def_readwrite("cthrust", &Propeller::cthrust, "coefficient of thrust")
.def_readwrite("ctorque", &Propeller::ctorque, "coefficient of torque")
.def_readwrite("type", &Propeller::type,
"type of propeller (clockwise or counterclockwise)")
.def(PrintableVisitor<Propeller>())
.def(CopyableVisitor<Propeller>());
":param ctorque: coefficient of generated torque per thrust\n"
":param type: type of thruster (clockwise or counterclockwise, "
"default clockwise)\n"
":param min_thrust: minimum thrust (default 0.)\n"
":param max_thrust: maximum thrust (default np.inf)"))
.def(bp::init<double, bp::optional<ThrusterType, double, double>>(
bp::args("self", "ctorque", "type", "min_thrust", "max_thrust"),
"Initialize the thruster in a give pose from the root joint.\n\n"
":param ctorque: coefficient of generated torque per thrust\n"
":param type: type of thruster (clockwise or counterclockwise, "
"default clockwise)\n"
":param min_thrust: minimum thrust (default 0.)\n"
":param max_thrust: maximum thrust (default np.inf)"))
.def_readwrite("pose", &Thruster::pose,
"thruster pose (traslation, rotation)")
.def_readwrite("ctorque", &Thruster::ctorque,
"coefficient of generated torque per thrust")
.def_readwrite("type", &Thruster::type,
"type of thruster (clockwise or counterclockwise)")
.def_readwrite("min_thrust", &Thruster::min_thrust, "minimum thrust")
.def_readwrite("max_thrust", &Thruster::min_thrust, "maximum thrust")
.def(PrintableVisitor<Thruster>())
.def(CopyableVisitor<Thruster>());

StdVectorPythonVisitor<std::vector<Propeller>, true>::expose(
"StdVec_Propeller");
StdVectorPythonVisitor<std::vector<Thruster>, true>::expose(
"StdVec_Thruster");

bp::register_ptr_to_python<
boost::shared_ptr<crocoddyl::ActuationModelFloatingBasePropellers>>();
boost::shared_ptr<crocoddyl::ActuationModelFloatingBaseThrusters>>();

bp::class_<ActuationModelFloatingBasePropellers,
bp::class_<ActuationModelFloatingBaseThrusters,
bp::bases<ActuationModelAbstract>>(
"ActuationModelFloatingBasePropellers",
"Actuation models for floating base systems actuated with propellers "
"ActuationModelFloatingBaseThrusters",
"Actuation models for floating base systems actuated with thrusters "
"(e.g. aerial "
"manipulators).",
bp::init<boost::shared_ptr<StateMultibody>, std::vector<Propeller>>(
bp::args("self", "state", "propellers"),
bp::init<boost::shared_ptr<StateMultibody>, std::vector<Thruster>>(
bp::args("self", "state", "thrusters"),
"Initialize the floating base actuation model equipped with "
"propellers.\n\n"
"thrusters.\n\n"
":param state: state of multibody system\n"
":param propellers: vector of propellers"))
.def<void (ActuationModelFloatingBasePropellers::*)(
":param thrusters: vector of thrusters"))
.def<void (ActuationModelFloatingBaseThrusters::*)(
const boost::shared_ptr<ActuationDataAbstract>&,
const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const Eigen::VectorXd>&)>(
"calc", &ActuationModelFloatingBasePropellers::calc,
"calc", &ActuationModelFloatingBaseThrusters::calc,
bp::args("self", "data", "x", "u"),
"Compute the actuation signal and actuation set from the thrust\n"
"forces and joint torque inputs u.\n\n"
":param data: floating base propellers actuation data\n"
":param data: floating base thrusters actuation data\n"
":param x: state point (dim. state.nx)\n"
":param u: joint torque input (dim. nu)")
.def(
"calcDiff", &ActuationModelFloatingBasePropellers::calcDiff,
bp::args("self", "data", "x", "u"),
"Compute the derivatives of the actuation model.\n\n"
"It computes the partial derivatives of the propeller actuation. It\n"
"assumes that calc has been run first. The reason is that the\n"
"derivatives are constant and defined in createData. The Hessian\n"
"is constant, so we don't write again this value.\n"
":param data: floating base propellers actuation data\n"
":param x: state point (dim. state.nx)\n"
":param u: joint torque input (dim. nu)")
.def("commands", &ActuationModelFloatingBasePropellers::commands,
.def("calcDiff", &ActuationModelFloatingBaseThrusters::calcDiff,
bp::args("self", "data", "x", "u"),
"Compute the derivatives of the actuation model.\n\n"
"It computes the partial derivatives of the thruster actuation. It\n"
"assumes that calc has been run first. The reason is that the\n"
"derivatives are constant and defined in createData. The Hessian\n"
"is constant, so we don't write again this value.\n"
":param data: floating base thrusters actuation data\n"
":param x: state point (dim. state.nx)\n"
":param u: joint torque input (dim. nu)")
.def("commands", &ActuationModelFloatingBaseThrusters::commands,
bp::args("self", "data", "x", "tau"),
"Compute the thrust and joint torque commands from the generalized "
"torques.\n\n"
Expand All @@ -103,40 +101,40 @@ void exposeActuationFloatingBasePropeller() {
":param x: state point (dim. state.nx)\n"
":param tau: generalized torques (dim state.nv)")
.def("torqueTransform",
&ActuationModelFloatingBasePropellers::torqueTransform,
&ActuationModelFloatingBaseThrusters::torqueTransform,
bp::args("self", "data", "x", "tau"),
"Compute the torque transform from generalized torques to thrust "
"and joint torque inputs.\n\n"
"It stores the results in data.Mtau.\n"
":param data: floating base propellers actuation data\n"
":param data: floating base thrusters actuation data\n"
":param x: state point (dim. state.nx)\n"
":param tau: generalized torques (dim state.nv)")
.def("createData", &ActuationModelFloatingBasePropellers::createData,
.def("createData", &ActuationModelFloatingBaseThrusters::createData,
bp::args("self"),
"Create the floating base propellers actuation data.")
.add_property("propellers",
bp::make_function(
&ActuationModelFloatingBasePropellers::get_propellers,
bp::return_value_policy<bp::return_by_value>()),
bp::make_function(
&ActuationModelFloatingBasePropellers::set_propellers),
"vector of propellers")
.add_property("npropellers",
"Create the floating base thrusters actuation data.")
.add_property(
"thrusters",
bp::make_function(&ActuationModelFloatingBaseThrusters::get_thrusters,
bp::return_value_policy<bp::return_by_value>()),
bp::make_function(
&ActuationModelFloatingBaseThrusters::set_thrusters),
"vector of thrusters")
.add_property("nthrusters",
bp::make_function(
&ActuationModelFloatingBasePropellers::get_npropellers),
"number of propellers")
&ActuationModelFloatingBaseThrusters::get_nthrusters),
"number of thrusters")
.add_property(
"Wthrust",
bp::make_function(&ActuationModelFloatingBasePropellers::get_Wthrust,
bp::make_function(&ActuationModelFloatingBaseThrusters::get_Wthrust,
bp::return_value_policy<bp::return_by_value>()),
"matrix mapping from thrusts to propeller wrenches")
"matrix mapping from thrusts to thruster wrenches")
.add_property(
"S",
bp::make_function(&ActuationModelFloatingBasePropellers::get_S,
bp::make_function(&ActuationModelFloatingBaseThrusters::get_S,
bp::return_value_policy<bp::return_by_value>()),
"selection matrix for under-actuation part")
.def(PrintableVisitor<ActuationModelFloatingBasePropellers>())
.def(CopyableVisitor<ActuationModelFloatingBasePropellers>());
.def(PrintableVisitor<ActuationModelFloatingBaseThrusters>())
.def(CopyableVisitor<ActuationModelFloatingBaseThrusters>());
}

} // namespace python
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/crocoddyl/multibody/multibody.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ void exposeMultibody() {
exposeStateMultibody();
exposeActuationFloatingBase();
exposeActuationFull();
exposeActuationFloatingBasePropeller();
exposeActuationFloatingBaseThruster();
exposeActuationModelMultiCopterBase();
exposeForceAbstract();
exposeContactAbstract();
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/crocoddyl/multibody/multibody.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void exposeCoPSupport();
void exposeStateMultibody();
void exposeActuationFloatingBase();
void exposeActuationFull();
void exposeActuationFloatingBasePropeller();
void exposeActuationFloatingBaseThruster();
void exposeActuationModelMultiCopterBase();
void exposeForceAbstract();
void exposeContactAbstract();
Expand Down
42 changes: 13 additions & 29 deletions examples/quadrotor_fwddyn.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,46 +21,30 @@

state = crocoddyl.StateMultibody(robot_model)

d_cog, cf, cm, u_lim, l_lim = 0.1525, 6.6e-5, 1e-6, 5.0, 0.1
tau_f = np.array(
[
[0.0, 0.0, 0.0, 0.0],
[0.0, 0.0, 0.0, 0.0],
[1.0, 1.0, 1.0, 1.0],
[0.0, d_cog, 0.0, -d_cog],
[-d_cog, 0.0, d_cog, 0.0],
[-cm / cf, cm / cf, -cm / cf, cm / cf],
]
)

d_cog, cf, cm, u_lim, l_lim = 0.1525, 6.6e-5, 1e-6, 5.0, 0.1
ps = [
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([-d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, -d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
]
actuation = crocoddyl.ActuationModelFloatingBasePropellers(state, ps)
actuation = crocoddyl.ActuationModelFloatingBaseThrusters(state, ps)

nu = actuation.nu
runningCostModel = crocoddyl.CostModelSum(state, nu)
Expand Down
30 changes: 13 additions & 17 deletions examples/quadrotor_invdyn.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,32 +23,28 @@

d_cog, cf, cm, u_lim, l_lim = 0.1525, 6.6e-5, 1e-6, 5.0, 0.1
ps = [
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([-d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, -d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
]
actuation = crocoddyl.ActuationModelFloatingBasePropellers(state, ps)
actuation = crocoddyl.ActuationModelFloatingBaseThrusters(state, ps)

nu = state.nv
runningCostModel = crocoddyl.CostModelSum(state, nu)
Expand Down
30 changes: 13 additions & 17 deletions examples/quadrotor_ubound.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,32 +23,28 @@

d_cog, cf, cm, u_lim, l_lim = 0.1525, 6.6e-5, 1e-6, 5.0, 0.1
ps = [
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([-d_cog, 0, 0])),
cf,
cm,
crocoddyl.PropellerType.CCW,
cm / cf,
crocoddyl.ThrusterType.CCW,
),
crocoddyl.Propeller(
crocoddyl.Thruster(
pinocchio.SE3(np.eye(3), np.array([0, -d_cog, 0])),
cf,
cm,
crocoddyl.PropellerType.CW,
cm / cf,
crocoddyl.ThrusterType.CW,
),
]
actuation = crocoddyl.ActuationModelFloatingBasePropellers(state, ps)
actuation = crocoddyl.ActuationModelFloatingBaseThrusters(state, ps)

nu = actuation.nu
runningCostModel = crocoddyl.CostModelSum(state, nu)
Expand Down
Loading

0 comments on commit fd0787e

Please sign in to comment.