scenario::monopod C++ API

scenario::monopod::World

class scenario::monopod::World : public World, public std::enable_shared_from_this<scenario::monopod::World>

Public Functions

bool initialize(const monopod_drivers::Mode &mode, const bool &dummy_mode = false) const

Initialize can_bus connections to encoder board and motor board.

Parameters
  • monopod_mode – defines the task mode of the monopod. Can also specify individual boards.

  • dummy_mode – if false the sdk will try to connect to the canbus connection otherwise it will just create a dummy board class which fakes the real robot.

bool valid() const override

Check if the world is valid.

Returns

True if the world is valid, false otherwise.

std::string name() const override

Get the name of the world.

Returns

The name of the world.

std::vector<std::string> modelNames() const override

Get the name of the models that are part of the world.

Returns

The list of model names.

scenario::core::ModelPtr getModel(const std::string &modelName) const override

Get a model part of the world.

Parameters

modelName – The name of the model to get.

Returns

The model if it is part of the world, nullptr otherwise.

std::vector<scenario::core::ModelPtr> models(const std::vector<std::string> &modelNames = {}) const override

Get the models of the world.

Parameters

modelNames – Optional vector of considered models. By default, World::modelNames is used.

Returns

A vector of pointers to the model objects.

scenario::monopod::Model

class scenario::monopod::Model : public Model, public std::enable_shared_from_this<scenario::monopod::Model>

Public Types

typedef monopod_drivers::Mode Mode

A useful shortcut for using cpp scenario code.

Public Functions

bool initialize(const monopod_drivers::Mode &mode, const bool &dummy_mode) const

Initialize can_bus connections to encoder board and motor board.

Parameters
  • monopod_mode – defines the task mode of the monopod. Can also specify individual boards.

  • dummy_mode – if false the sdk will try to connect to the canbus connection otherwise it will just create a dummy board class which fakes the real robot.

void calibrate(const double &hip_home_offset_rad = 0, const double &knee_home_offset_rad = 0)

Calibrate the Encoders.

Parameters
  • hip_home_offset_rad – hip offset from found encoder index 0 (rad)

  • knee_home_offset_rad – knee offset from found encoder index 0 (rad)

void reset()

If the joint module is not valid (safemode after limit reached) the joint will be reset into a valid state. This means the joint must be set back into the valid state first otherwise it will trigger the limits again.

void print_status()

print status messages of robot.

bool valid() const override

Check if the model is valid.

Returns

True if the model is valid, false otherwise.

std::string name() const override

Get the name of the model.

Returns

The name of the model.

size_t dofs(const std::vector<std::string> &jointNames = {}) const override

Get the joints DOF

Parameters

jointNames – Optional vector of considered joints that also defines the joint serialization. By default, Model::jointNames is used.

Returns

The sum of serialization of joint DOFs. The sum is the number of DoFs of all the considered joints.

core::JointPtr getJoint(const std::string &jointName) const override

Get a joint belonging to the model.

Parameters

jointName – The name of the joint.

Throws

std::runtime_error – if the joint does not exist.

Returns

The desired joint.

std::vector<std::string> jointNames(const bool scoped = false) const override

Get the name of all the model’s joints.

Parameters

scoped – Scope the joint names with the model name, (e.g. mymodel::joint1).

Returns

The list of joint names.

std::vector<double> jointPositions(const std::vector<std::string> &jointNames = {}) const override

Get the joint positions.

Parameters

jointNames – Optional vector of considered joints that also defines the joint serialization. By default, Model::jointNames is used.

Returns

The serialization of joint positions. The vector has as many elements as DoFs of the considered joints.

std::vector<double> jointVelocities(const std::vector<std::string> &jointNames = {}) const override

Get the joint velocities.

Parameters

jointNames – Optional vector of considered joints that also defines the joint serialization. By default, Model::jointNames is used.

Returns

The serialization of joint velocities. The vector has as many elements as DoFs of the considered joints.

std::vector<double> jointAccelerations(const std::vector<std::string> &jointNames = {}) const override

Get the joint accelerations.

Parameters

jointNames – Optional vector of considered joints that also defines the joint serialization. By default, Model::jointNames is used.

Returns

The serialization of joint accelerations. The vector has as many elements as DoFs of the considered joints.

bool setJointControlMode(const core::JointControlMode mode, const std::vector<std::string> &jointNames = {}) override

Set the control mode of model joints.

Parameters
  • mode – The desired joint control mode.

  • jointNames – Optional vector of considered joints that also defines the joint serialization. By default, Model::jointNames is used.

Returns

True for success, false otherwise.

std::vector<core::JointPtr> joints(const std::vector<std::string> &jointNames = {}) const override

Get the joints of the model.

Parameters

jointNames – Optional vector of considered joints. By default, Model::jointNames is used.

Returns

A vector of pointers to the joint objects.

bool setJointGeneralizedForceTargets(const std::vector<double> &forces, const std::vector<std::string> &jointNames = {}) override

Set the generalized force targets of the joints.

Parameters
  • forces – The vector with the joint generalized force targets. It must have as many elements as the considered joint DoFs.

  • jointNames – Optional vector of considered joints. By default, Model::jointNames is used.

Returns

True for success, false otherwise.

std::vector<double> jointGeneralizedForceTargets(const std::vector<std::string> &jointNames = {}) const override

Get the generalized force targets of the joints.

Parameters

jointNames – Optional vector of considered joints. By default, Model::jointNames is used.

Returns

The generalized force targets of the joints.

scenario::monopod::Joint

class scenario::monopod::Joint : public Joint, public std::enable_shared_from_this<scenario::monopod::Joint>

Public Functions

bool valid() const override

Check if the joint is valid.

Returns

True if the model is valid, false otherwise.

size_t dofs() const override

Get the number of degrees of freedom of the joint.

Returns

The number of DOFs of the joint.

std::string name(const bool scoped = false) const override

Get the name of the joint.

Parameters

scoped – If true, the scoped name of the joint is returned.

Returns

The name of the joint.

core::JointType type() const override

Get the type of the joint.

Returns

The type of the joint.

bool setControlMode(const core::JointControlMode mode) override

Set the joint control mode.

Parameters

mode – The desired control mode.

Returns

True for success, false otherwise.

core::JointControlMode controlMode() const override

get the joint control mode.

Returns

the joint control mode

core::PID pid() const override

Get the PID parameters of the joint.

If no PID parameters have been set, the default parameters are returned.

Returns

The joint PID parameters.

bool setPID(const core::PID &pid) override

Set the PID parameters of the joint.

Parameters

pid – The desired PID parameters.

Returns

True for success, false otherwise.

std::vector<double> jointMaxGeneralizedForce() const override

Get the maximum generalized force that could be applied to the joint.

Returns

The maximum generalized force of the joint.

bool setJointMaxGeneralizedForce(const std::vector<double> &maxForce) override

Set the maximum generalized force that can be applied to the joint.

This limit can be used to clip the force applied by joint controllers.

Parameters

maxForce – A vector with the maximum generalized forces of the joint DOFs.

Returns

True for success, false otherwise.

std::vector<double> jointPosition() const override

Get the position of the joint.

Returns

The position of the joint.

std::vector<double> jointVelocity() const override

Get the velocity of the joint.

Returns

The velocity of the joint.

std::vector<double> jointAcceleration() const override

Get the acceleration of the joint.

Returns

The acceleration of the joint.

bool setJointGeneralizedForceTarget(const std::vector<double> &force) override

Set the generalized force target of the joint.

Note that if there’s friction or other loss components, the real joint force will differ.

Parameters

force – A vector with the generalized force targets of the joint DOFs.

Returns

True for success, false otherwise.

std::vector<double> jointGeneralizedForceTarget() const override

Get the active generalized force target.

Returns

The generalized force target of the joint.

core::JointLimit jointPositionLimit() const override

Get the position limits of the joint.

Returns

The position limits of the joint.

core::JointLimit jointVelocityLimit() const override

Get the velocity limits of the joint.

Returns

The velocity limits of the joint.

core::JointLimit jointAccelerationLimit() const

Get the acceleration limits of the joint.

Returns

The acceleration limits of the joint.

bool setJointPositionLimit(const double &maxPosition, const double &minPosition)

Set the maximum position of the joint.

This limit can be used to set safety limits on the joint position. when violated the Robot will enter into a safe mode. disabling the robot until it is reset or restart.

Parameters
  • maxPosition – maximum position of the joint DOFs.

  • minPosition – minimum position of the joint DOFs.

Returns

True for success, false otherwise.

bool setJointVelocityLimit(const double &maxVelocity, const double &minVelocity)

Set the maximum velocity of the joint.

This limit can be used to set safety limits on the joint velocity. when violated the Robot will enter into a safe mode. disabling the robot until it is reset or restart.

Parameters
  • maxVelocity – maximum velocity of the joint DOFs.

  • minVelocity – minimum position of the joint DOFs.

Returns

True for success, false otherwise.

bool setJointAccelerationLimit(const double &maxAcceleration, const double &minAcceleration)

Set the maximum acceleration of the joint.

This limit can be used to set safety limits on the joint acceleration. when violated the Robot will enter into a safe mode. disabling the robot until it is reset or restart.

Parameters
  • maxAcceleration – maximum acceleration of the joint DOFs.

  • minAcceleration – minimum acceleration of the joint DOFs.

Returns

True for success, false otherwise.