robot

class Model : public std::enable_shared_from_this<Model>

Subclassed by jiminy::Robot

Public Functions

inline virtual GenericConfig getDefaultJointOptions()
inline virtual GenericConfig getDefaultDynamicsOptions()
inline virtual GenericConfig getDefaultCollisionOptions()
inline virtual GenericConfig getDefaultModelOptions()
explicit Model() noexcept
virtual ~Model() = default
void initialize(const pinocchio::Model &pinocchioModel, const std::optional<pinocchio::GeometryModel> &collisionModel = std::nullopt, const std::optional<pinocchio::GeometryModel> &visualModel = std::nullopt)
void initialize(const std::string &urdfPath, bool hasFreeflyer = true, const std::vector<std::string> &meshPackageDirs = {}, bool loadVisualMeshes = false)
void addFrame(const std::string &frameName, const std::string &parentBodyName, const pinocchio::SE3 &framePlacement)

Add a frame in the kinematic tree, attached to the frame of an existing body.

Parameters:
  • frameName[in] Name of the frame to be added.

  • parentBodyName[in] Name of the parent body frame.

  • framePlacement[in] Frame placement wrt the parent body frame.

void removeFrames(const std::vector<std::string> &frameNames)
void addCollisionBodies(const std::vector<std::string> &bodyNames, bool ignoreMeshes = false)
void removeCollisionBodies(std::vector<std::string> frameNames = {})
void addContactPoints(const std::vector<std::string> &frameNames)
void removeContactPoints(const std::vector<std::string> &frameNames = {})
void addConstraint(const std::string &constraintName, const std::shared_ptr<AbstractConstraintBase> &constraint)

Add a kinematic constraint to the robot.

Parameters:
  • constraintName[in] Unique name identifying the kinematic constraint.

  • constraint[in] Constraint to add.

void removeConstraint(const std::string &constraintName)

Remove a kinematic constraint form the system.

Parameters:

constraintName[in] Unique name identifying the kinematic constraint.

std::shared_ptr<AbstractConstraintBase> getConstraint(const std::string &constraintName)

Pointer to the constraint referenced by constraintName.

Parameters:

constraintName[in] Name of the constraint to get.

std::weak_ptr<const AbstractConstraintBase> getConstraint(const std::string &constraintName) const
const ConstraintTree &getConstraints() const
bool existConstraint(const std::string &constraintName) const
bool hasConstraints() const

Returns true if at least one constraint is active on the robot.

void resetConstraints(const Eigen::VectorXd &q, const Eigen::VectorXd &v)
void computeConstraints(const Eigen::VectorXd &q, const Eigen::VectorXd &v)

Compute jacobian and drift associated to all the constraints.

The results are accessible using getConstraintsJacobian and getConstraintsDrift.

Note

It is assumed frames forward kinematics has already been called.

Parameters:
  • q[in] Joint position.

  • v[in] Joint velocity.

void setOptions(const GenericConfig &modelOptions)
const GenericConfig &getOptions() const noexcept
virtual void reset(const uniform_random_bit_generator_ref<uint32_t> &g)

Remark

This method does not have to be called manually before running a simulation. The Engine is taking care of it.

bool getIsInitialized() const
const std::string &getName() const
const std::string &getUrdfPath() const
const std::string &getUrdfAsString() const
const std::vector<std::string> &getMeshPackageDirs() const
bool getHasFreeflyer() const
Eigen::Index nq() const
Eigen::Index nv() const
Eigen::Index nx() const
const std::vector<std::string> &getCollisionBodyNames() const
const std::vector<std::string> &getContactFrameNames() const
const std::vector<pinocchio::FrameIndex> &getCollisionBodyIndices() const
const std::vector<std::vector<pinocchio::PairIndex>> &getCollisionPairIndices() const
const std::vector<pinocchio::FrameIndex> &getContactFrameIndices() const
const std::vector<std::string> &getMechanicalJointNames() const
const std::vector<pinocchio::JointIndex> &getMechanicalJointIndices() const
const std::vector<Eigen::Index> &getMechanicalJointPositionIndices() const
const std::vector<Eigen::Index> &getMechanicalJointVelocityIndices() const
const std::vector<std::string> &getFlexibilityJointNames() const
const std::vector<pinocchio::JointIndex> &getFlexibilityJointIndices() const
const std::vector<std::string> &getBacklashJointNames() const
const std::vector<pinocchio::JointIndex> &getBacklashJointIndices() const
const Eigen::VectorXd &getPositionLimitMin() const
const Eigen::VectorXd &getPositionLimitMax() const
const Eigen::VectorXd &getVelocityLimit() const
const std::vector<std::string> &getLogPositionFieldnames() const
const std::vector<std::string> &getLogVelocityFieldnames() const
const std::vector<std::string> &getLogAccelerationFieldnames() const
const std::vector<std::string> &getLogForceExternalFieldnames() const
void getExtendedPositionFromTheoretical(const Eigen::VectorXd &qTheoretical, Eigen::VectorXd &qExtended) const
void getExtendedVelocityFromTheoretical(const Eigen::VectorXd &vTheoretical, Eigen::VectorXd &vExtended) const
void getTheoreticalPositionFromExtended(const Eigen::VectorXd &qExtended, Eigen::VectorXd &qTheoretical) const
void getTheoreticalVelocityFromExtended(const Eigen::VectorXd &vExtended, Eigen::VectorXd &vTheoretical) const

Public Members

pinocchio::Model pinocchioModelTh_ = {}
pinocchio::Model pinocchioModel_ = {}
pinocchio::GeometryModel collisionModelTh_ = {}
pinocchio::GeometryModel collisionModel_ = {}
pinocchio::GeometryModel visualModelTh_ = {}
pinocchio::GeometryModel visualModel_ = {}
mutable pinocchio::Data pinocchioDataTh_ = {}
mutable pinocchio::Data pinocchioData_ = {}
mutable pinocchio::GeometryData collisionData_ = {}
mutable pinocchio::GeometryData visualData_ = {}
std::unique_ptr<const ModelOptions> modelOptions_ = {nullptr}
ForceVector contactForces_ = {}

Buffer storing the contact forces.

struct CollisionOptions

Public Functions

inline CollisionOptions(const GenericConfig &options)

Public Members

const uint32_t contactPointsPerBodyMax
struct DynamicsOptions

Public Functions

inline DynamicsOptions(const GenericConfig &options)

Public Members

const double inertiaBodiesBiasStd
const double massBodiesBiasStd
const double centerOfMassPositionBodiesBiasStd
const double relativePositionBodiesBiasStd
const bool enableFlexibility
const FlexibilityConfig flexibilityConfig
struct JointOptions

Public Functions

inline JointOptions(const GenericConfig &options)

Public Members

const bool positionLimitFromUrdf
const Eigen::VectorXd positionLimitMin

Min position limit of all the mechanical joints of the theoretical model.

const Eigen::VectorXd positionLimitMax
const bool enableVelocityLimit
const bool velocityLimitFromUrdf
const Eigen::VectorXd velocityLimit
struct ModelOptions

Public Functions

inline ModelOptions(const GenericConfig &options)

Public Members

const DynamicsOptions dynamics
const JointOptions joints
const CollisionOptions collisions
class Robot : public jiminy::Model

Public Types

using MotorVector = std::vector<std::shared_ptr<AbstractMotorBase>>
using SensorVector = std::vector<std::shared_ptr<AbstractSensorBase>>
using SensorTree = std::unordered_map<std::string, SensorVector>

Public Functions

inline virtual GenericConfig getDefaultRobotOptions()
explicit Robot(const std::string &name = "") noexcept
Parameters:

name[in] Name of the Robot.

virtual ~Robot()
inline auto shared_from_this()
inline auto shared_from_this() const
void initialize(const pinocchio::Model &pinocchioModel, const std::optional<pinocchio::GeometryModel> &collisionModel = std::nullopt, const std::optional<pinocchio::GeometryModel> &visualModel = std::nullopt)
void initialize(const std::string &urdfPath, bool hasFreeflyer = true, const std::vector<std::string> &meshPackageDirs = {}, bool loadVisualMeshes = false)
const std::string &getName() const
void attachMotor(std::shared_ptr<AbstractMotorBase> motor)
std::shared_ptr<AbstractMotorBase> getMotor(const std::string &motorName)
std::weak_ptr<const AbstractMotorBase> getMotor(const std::string &motorName) const
const MotorVector &getMotors() const
void detachMotor(const std::string &motorName)
void detachMotors(std::vector<std::string> motorNames = {})
void attachSensor(std::shared_ptr<AbstractSensorBase> sensor)
std::shared_ptr<AbstractSensorBase> getSensor(const std::string &sensorType, const std::string &sensorName)
std::weak_ptr<const AbstractSensorBase> getSensor(const std::string &sensorType, const std::string &sensorName) const
const SensorTree &getSensors() const
void detachSensor(const std::string &sensorType, const std::string &sensorName)
void detachSensors(const std::string &sensorType = {})
void setController(const std::shared_ptr<AbstractController> &controller)
std::shared_ptr<AbstractController> getController()
std::weak_ptr<const AbstractController> getController() const
void computeMotorEfforts(double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const Eigen::VectorXd &command)
const Eigen::VectorXd &getMotorEfforts() const
double getMotorEffort(const std::string &motorName) const
void computeSensorMeasurements(double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const Eigen::VectorXd &uMotor, const ForceVector &fExternal)

Warning

It assumes that kinematic quantities have been updated previously and are consistent with the following input arguments. If not, one must call pinocchio::forwardKinematics and pinocchio::updateFramePlacements beforehand.

SensorMeasurementTree getSensorMeasurements() const
Eigen::Ref<const Eigen::VectorXd> getSensorMeasurement(const std::string &sensorType, const std::string &sensorName) const
void setOptions(const GenericConfig &robotOptions)
const GenericConfig &getOptions() const noexcept
void setModelOptions(const GenericConfig &modelOptions)
const GenericConfig &getModelOptions() const noexcept
virtual void reset(const uniform_random_bit_generator_ref<uint32_t> &g) override

Remark

This method does not have to be called manually before running a simulation. The Engine is taking care of it.

virtual void configureTelemetry(std::shared_ptr<TelemetryData> telemetryData)
void updateTelemetry()
bool getIsTelemetryConfigured() const
const std::vector<std::string> &getMotorNames() const
std::vector<pinocchio::JointIndex> getMotorJointIndices() const
std::vector<std::vector<Eigen::Index>> getMotorsPositionIndices() const
std::vector<Eigen::Index> getMotorVelocityIndices() const
const std::unordered_map<std::string, std::vector<std::string>> &getSensorNames() const
const std::vector<std::string> &getSensorNames(const std::string &sensorType) const
const Eigen::VectorXd &getCommandLimit() const
const std::vector<std::string> &getLogCommandFieldnames() const
const std::vector<std::string> &getLogMotorEffortFieldnames() const
Eigen::Index nmotors() const
std::unique_ptr<LockGuardLocal> getLock()
bool getIsLocked() const