upkie 6.1.0
Open-source wheeled biped robots
Loading...
Searching...
No Matches
upkie::cpp::actuation::BulletInterface Class Reference

Actuation interface for the Bullet simulator. More...

#include <BulletInterface.h>

Classes

struct  Parameters
 Interface parameters. More...
 

Public Member Functions

 BulletInterface (const Parameters &params)
 Initialize interface. More...
 
 ~BulletInterface ()
 Disconnect interface.
 
void reset (const Dictionary &config) override
 Reset interface. More...
 
void observe (Dictionary &observation) const override
 Write actuation-interface observations to dictionary. More...
 
void process_action (const Dictionary &action) override
 Process a new action dictionary. More...
 
void process_forces (const Dictionary &external_forces)
 Process a dictionary of additional external forces. More...
 
void cycle (std::function< void(const moteus::Output &)> callback) final
 Spin a new communication cycle. More...
 
Eigen::Matrix4d get_transform_base_to_world () const noexcept
 Get the groundtruth floating base transform.
 
Eigen::Matrix4d get_transform_body_to_world (int body_id) const noexcept
 Get a groundtruth body transform. More...
 
Eigen::Vector3d get_linear_velocity_base_to_world_in_world () const noexcept
 Get the groundtruth floating base linear velocity. More...
 
Eigen::Vector3d get_angular_velocity_base_in_base () const noexcept
 Get the groundtruth floating base angular velocity. More...
 
Eigen::VectorXd get_joint_angles () noexcept
 Get the groundtruth vector of joint angles. More...
 
void reset_contact_data ()
 Reset contact data.
 
void reset_joint_angles (const Eigen::VectorXd &joint_configuration)
 Reset joint angles. More...
 
void reset_joint_properties ()
 Reset joint properties to defaults.
 
void reset_base_state (const Eigen::Vector3d &position_base_in_world, const Eigen::Quaterniond &orientation_base_in_world, const Eigen::Vector3d &linear_velocity_base_to_world_in_world, const Eigen::Vector3d &angular_velocity_base_in_base)
 Reset the pose and velocity of the floating base in the world frame. More...
 
const std::map< std::string, bullet::JointProperties > & joint_properties ()
 Joint properties (getter used for testing)
 
const std::map< std::string, moteus::ServoReply > & servo_reply ()
 Internal map of servo replies (getter used for testing)
 
double compute_joint_torque (const std::string &joint_name, const double feedforward_torque, const double target_position, const double target_velocity, const double kp_scale, const double kd_scale, const double maximum_torque)
 Reproduce the moteus position controller in Bullet. More...
 
double compute_robot_mass ()
 Compute total robot mass in kg.
 
Eigen::Vector3d compute_position_com_in_world ()
 Compute the position of the center of mass in the world frame.
 
Eigen::Vector3d get_position_link_in_world (const std::string &link_name)
 Compute the position of a link frame in the world frame. More...
 
void save_nominal_masses ()
 Get nominal masses of the robot links.
 
void randomize_masses ()
 Randomize masses of the robot links.
 
- Public Member Functions inherited from upkie::cpp::actuation::Interface
 Interface ()
 Initialize actuation interface for a given servo layout.
 
virtual ~Interface ()=default
 Virtual destructor so that derived destructors are called properly.
 
virtual void cycle (std::function< void(const moteus::Output &)> callback)=0
 Spin a new communication cycle. More...
 
virtual void reset (const Dictionary &config)=0
 Reset interface. More...
 
virtual void observe (Dictionary &observation) const =0
 Write servo and IMU observations to dictionary. More...
 
const ServoLayoutservo_layout () const noexcept
 Get servo layout.
 
const std::map< int, int > & servo_bus_map () const noexcept
 Map from servo ID to the CAN bus the servo is connected to.
 
const std::map< int, std::string > & servo_name_map () const noexcept
 Map from servo ID to joint name.
 
std::vector< moteus::ServoCommand > & commands ()
 Get servo commands.
 
const std::vector< moteus::ServoReply > & replies () const
 Get servo replies.
 
moteus::Data & data ()
 Get joint command-reply data. More...
 
void reset_action (Dictionary &action)
 Reset action dictionary to the default action. More...
 
virtual void process_action (const Dictionary &action)=0
 Process a new action dictionary. More...
 
void write_position_commands (const Dictionary &action)
 Write position commands from an action dictionary. More...
 
void write_stop_commands () noexcept
 Stop all servos. More...
 
void observe_imu (Dictionary &observation) const
 Observe IMU measurements. More...
 

Public Attributes

double inertia_randomization_
 Mass randomization epsilon.
 
std::map< int, double > nominal_masses
 Nominal masses of the robot links.
 
std::map< int, double[3]> nominal_inertia
 Nominal inertia diagonal of the robot links.
 

Additional Inherited Members

- Protected Attributes inherited from upkie::cpp::actuation::Interface
moteus::Data data_
 Pointers to the memory shared with the CAN thread. More...
 
ImuData imu_data_
 IMU data.
 

Detailed Description

Actuation interface for the Bullet simulator.

Constructor & Destructor Documentation

◆ BulletInterface()

upkie::cpp::actuation::BulletInterface::BulletInterface ( const Parameters params)
explicit

Initialize interface.

Parameters
[in]paramsInterface parameters.
Exceptions
std::runtime_errorIf the simulator did not start properly.

Member Function Documentation

◆ compute_joint_torque()

double upkie::cpp::actuation::BulletInterface::compute_joint_torque ( const std::string &  joint_name,
const double  feedforward_torque,
const double  target_position,
const double  target_velocity,
const double  kp_scale,
const double  kd_scale,
const double  maximum_torque 
)

Reproduce the moteus position controller in Bullet.

Parameters
[in]joint_nameName of the joint.
[in]feedforward_torqueFeedforward torque command in [N m].
[in]target_positionTarget angular position in [rad].
[in]target_velocityTarget angular velocity in [rad] / [s].
[in]kp_scaleMultiplicative factor applied to the proportional gain in torque control.
[in]kd_scaleMultiplicative factor applied to the derivative gain in torque control.
[in]maximum_torqueMaximum torque in [N m] from the command.

◆ cycle()

void upkie::cpp::actuation::BulletInterface::cycle ( std::function< void(const moteus::Output &)>  callback)
finalvirtual

Spin a new communication cycle.

Parameters
callbackFunction to call when the cycle is over.

The callback will be invoked from an arbitrary thread when the communication cycle has completed. All memory pointed to by data must remain valid until the callback is invoked.

Implements upkie::cpp::actuation::Interface.

◆ get_angular_velocity_base_in_base()

Eigen::Vector3d upkie::cpp::actuation::BulletInterface::get_angular_velocity_base_in_base ( ) const
noexcept

Get the groundtruth floating base angular velocity.

Note
This function is only used for testing and does not need to be optimized.

◆ get_joint_angles()

Eigen::VectorXd upkie::cpp::actuation::BulletInterface::get_joint_angles ( )
noexcept

Get the groundtruth vector of joint angles.

Note
This function is only used for testing and does not need to be optimized.

◆ get_linear_velocity_base_to_world_in_world()

Eigen::Vector3d upkie::cpp::actuation::BulletInterface::get_linear_velocity_base_to_world_in_world ( ) const
noexcept

Get the groundtruth floating base linear velocity.

Note
This function is only used for testing and does not need to be optimized.

◆ get_position_link_in_world()

Eigen::Vector3d upkie::cpp::actuation::BulletInterface::get_position_link_in_world ( const std::string &  link_name)

Compute the position of a link frame in the world frame.

Parameters
[in]link_nameName of the link in the robot description.

◆ get_transform_body_to_world()

Eigen::Matrix4d upkie::cpp::actuation::BulletInterface::get_transform_body_to_world ( int  body_id) const
noexcept

Get a groundtruth body transform.

Parameters
[in]body_idThe body id as given when loading the body in bullet.

◆ observe()

void upkie::cpp::actuation::BulletInterface::observe ( Dictionary &  observation) const
overridevirtual

Write actuation-interface observations to dictionary.

Parameters
[out]observationDictionary to write to.

Implements upkie::cpp::actuation::Interface.

◆ process_action()

void upkie::cpp::actuation::BulletInterface::process_action ( const Dictionary &  action)
overridevirtual

Process a new action dictionary.

Parameters
[in]actionAction to read commands from.

Implements upkie::cpp::actuation::Interface.

◆ process_forces()

void upkie::cpp::actuation::BulletInterface::process_forces ( const Dictionary &  external_forces)

Process a dictionary of additional external forces.

Parameters
[in]external_forcesDictionary to read forces from.

Note that Bullet clears external forces after each simulation step.

◆ reset()

void upkie::cpp::actuation::BulletInterface::reset ( const Dictionary &  config)
overridevirtual

Reset interface.

Parameters
[in]configAdditional configuration dictionary.

Implements upkie::cpp::actuation::Interface.

◆ reset_base_state()

void upkie::cpp::actuation::BulletInterface::reset_base_state ( const Eigen::Vector3d &  position_base_in_world,
const Eigen::Quaterniond &  orientation_base_in_world,
const Eigen::Vector3d &  linear_velocity_base_to_world_in_world,
const Eigen::Vector3d &  angular_velocity_base_in_base 
)

Reset the pose and velocity of the floating base in the world frame.

Parameters
[in]position_base_in_worldPosition of the base in the world frame.
[in]orientation_base_in_worldOrientation of the base in the world frame.
[in]linear_velocity_base_to_world_in_worldLinear velocity of the base in the world frame.
[in]angular_velocity_base_in_baseBody angular velocity of the base (in the base frame).

◆ reset_joint_angles()

void upkie::cpp::actuation::BulletInterface::reset_joint_angles ( const Eigen::VectorXd &  joint_configuration)

Reset joint angles.

Parameters
[in]joint_configurationJoint configuration vector.

The documentation for this class was generated from the following files: