vulp  2.3.0
vulp::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 ServoLayout &layout, const Parameters &params)
 Initialize interface. More...
 
 ~BulletInterface ()
 Disconnect interface. More...
 
void reset (const Dictionary &config) override
 Reset interface. More...
 
void cycle (const moteus::Data &data, std::function< void(const moteus::Output &)> callback) final
 Spin a new communication cycle. More...
 
void observe (Dictionary &observation) const override
 Write actuation-interface observations to dictionary. More...
 
Eigen::Matrix4d transform_base_to_world () const noexcept
 Get the groundtruth floating base transform. More...
 
Eigen::Vector3d linear_velocity_base_to_world_in_world () const noexcept
 Get the groundtruth floating base linear velocity. More...
 
Eigen::Vector3d angular_velocity_base_in_base () const noexcept
 Get the groundtruth floating base angular velocity. More...
 
void reset_contact_data ()
 Reset contact data. More...
 
void reset_joint_angles ()
 Reset joint angles to zero. More...
 
void reset_joint_properties ()
 Reset joint properties to defaults. More...
 
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, BulletJointProperties > & joint_properties ()
 Joint properties (accessor used for testing) More...
 
const std::map< std::string, moteus::ServoReply > & servo_reply ()
 Internal map of servo replies (accessor used for testing) More...
 
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...
 
- Public Member Functions inherited from vulp::actuation::Interface
 Interface (const ServoLayout &servo_layout)
 Initialize actuation interface for a given servo layout. More...
 
virtual ~Interface ()=default
 Virtual destructor so that derived destructors are called properly. More...
 
const ServoLayoutservo_layout () const noexcept
 Get servo layout. More...
 
const std::map< int, int > & servo_bus_map () const noexcept
 Map from servo ID to the CAN bus the servo is connected to. More...
 
const std::map< int, std::string > & servo_joint_map () const noexcept
 Map from servo ID to joint name. More...
 
std::vector< moteus::ServoCommand > & commands ()
 Get servo commands. More...
 
const std::vector< moteus::ServoReply > & replies () const
 Get servo replies. More...
 
moteus::Data & data ()
 Get joint command-reply data. More...
 
void initialize_action (Dictionary &action)
 Initialize action dictionary with keys corresponding to the servo layout. 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...
 

Detailed Description

Actuation interface for the Bullet simulator.

Definition at line 25 of file BulletInterface.h.

Constructor & Destructor Documentation

◆ BulletInterface()

vulp::actuation::BulletInterface::BulletInterface ( const ServoLayout layout,
const Parameters params 
)

Initialize interface.

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

Definition at line 27 of file BulletInterface.cpp.

◆ ~BulletInterface()

vulp::actuation::BulletInterface::~BulletInterface ( )

Disconnect interface.

Definition at line 108 of file BulletInterface.cpp.

Member Function Documentation

◆ angular_velocity_base_in_base()

Eigen::Vector3d vulp::actuation::BulletInterface::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.

Definition at line 334 of file BulletInterface.cpp.

◆ compute_joint_torque()

double vulp::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.

Definition at line 289 of file BulletInterface.cpp.

◆ cycle()

void vulp::actuation::BulletInterface::cycle ( const moteus::Data &  data,
std::function< void(const moteus::Output &)>  callback 
)
finalvirtual

Spin a new communication cycle.

Parameters
dataBuffer to read commands from and write replies to.
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 vulp::actuation::Interface.

Definition at line 186 of file BulletInterface.cpp.

◆ joint_properties()

const std::map<std::string, BulletJointProperties>& vulp::actuation::BulletInterface::joint_properties ( )
inline

Joint properties (accessor used for testing)

Definition at line 243 of file BulletInterface.h.

◆ linear_velocity_base_to_world_in_world()

Eigen::Vector3d vulp::actuation::BulletInterface::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.

Definition at line 326 of file BulletInterface.cpp.

◆ observe()

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

Write actuation-interface observations to dictionary.

Parameters
[out]observationDictionary to write ot.

Implements vulp::actuation::Interface.

Definition at line 170 of file BulletInterface.cpp.

◆ reset()

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

Reset interface.

Parameters
[in]configAdditional configuration dictionary.

Implements vulp::actuation::Interface.

Definition at line 110 of file BulletInterface.cpp.

◆ reset_base_state()

void vulp::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).

Definition at line 122 of file BulletInterface.cpp.

◆ reset_contact_data()

void vulp::actuation::BulletInterface::reset_contact_data ( )

Reset contact data.

Definition at line 140 of file BulletInterface.cpp.

◆ reset_joint_angles()

void vulp::actuation::BulletInterface::reset_joint_angles ( )

Reset joint angles to zero.

Definition at line 146 of file BulletInterface.cpp.

◆ reset_joint_properties()

void vulp::actuation::BulletInterface::reset_joint_properties ( )

Reset joint properties to defaults.

Definition at line 153 of file BulletInterface.cpp.

◆ servo_reply()

const std::map<std::string, moteus::ServoReply>& vulp::actuation::BulletInterface::servo_reply ( )
inline

Internal map of servo replies (accessor used for testing)

Definition at line 248 of file BulletInterface.h.

◆ transform_base_to_world()

Eigen::Matrix4d vulp::actuation::BulletInterface::transform_base_to_world ( ) const
noexcept

Get the groundtruth floating base transform.

Definition at line 314 of file BulletInterface.cpp.


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