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

Bullet utility functions used in the simulation interface. More...

Classes

struct  ContactData
 Contact information for a single link. More...
 
struct  ExternalForce
 Parameters for a call to Bullet's applyExternalForce. More...
 
struct  JointProperties
 Properties for robot joints in the Bullet simulation. More...
 
struct  RobotSimulatorChangeDynamicsArgs
 Structure which contains the new link properties. More...
 
class  RobotSimulatorClientAPI
 Child class to enable modification of inertia matrices. More...
 

Functions

void read_imu_data (ImuData &imu_data, b3RobotSimulatorClientAPI &bullet, int robot, const int imu_link_index, double dt)
 Compute groundtruth IMU quantities from the IMU link state. More...
 
btQuaternion bullet_from_eigen (const Eigen::Quaterniond &quat)
 Convert an Eigen quaternion to a Bullet one. More...
 
btVector3 bullet_from_eigen (const Eigen::Vector3d &v)
 Convert an Eigen vector to a Bullet one. More...
 
Eigen::Quaterniond eigen_from_bullet (const btQuaternion &quat)
 Convert a Bullet quaternion to an Eigen one. More...
 
Eigen::Vector3d eigen_from_bullet (const btVector3 &v)
 Convert a Bullet vector to an Eigen one. More...
 
int find_link_index (b3RobotSimulatorClientAPI &bullet, int robot, const std::string &link_name) noexcept
 Find the index of a link. More...
 
Eigen::Vector3d get_position_link_in_world (b3RobotSimulatorClientAPI &bullet, int robot, int link_index) noexcept
 Get the position of a link frame in the world frame. More...
 
double compute_robot_mass (b3RobotSimulatorClientAPI &bullet, int robot)
 Get the total mass of the robot. More...
 
Eigen::Vector3d compute_position_com_in_world (b3RobotSimulatorClientAPI &bullet, int robot)
 Get the position of the center of mass of a robot in the world frame. More...
 

Variables

constexpr double kGravity = 9.81
 Standard gravity constant used in Bullet simulations.
 

Detailed Description

Bullet utility functions used in the simulation interface.

Function Documentation

◆ bullet_from_eigen() [1/2]

btQuaternion upkie::cpp::actuation::bullet::bullet_from_eigen ( const Eigen::Quaterniond &  quat)
inline

Convert an Eigen quaternion to a Bullet one.

Parameters
[in]quatEigen quaternion.
Returns
Same quaternion for Bullet.

◆ bullet_from_eigen() [2/2]

btVector3 upkie::cpp::actuation::bullet::bullet_from_eigen ( const Eigen::Vector3d &  v)
inline

Convert an Eigen vector to a Bullet one.

Parameters
[in]vEigen vector.
Returns
Same vector for Bullet.

◆ compute_position_com_in_world()

Eigen::Vector3d upkie::cpp::actuation::bullet::compute_position_com_in_world ( b3RobotSimulatorClientAPI &  bullet,
int  robot 
)
inline

Get the position of the center of mass of a robot in the world frame.

Parameters
[in]bulletBullet client.
[in]robotIndex of the robot.
Returns
Position of the center of mass in the world frame.
Note
This function will recompute forward kinematics.

◆ compute_robot_mass()

double upkie::cpp::actuation::bullet::compute_robot_mass ( b3RobotSimulatorClientAPI &  bullet,
int  robot 
)
inline

Get the total mass of the robot.

Parameters
[in]bulletBullet client.
[in]robotIndex of the robot.
Returns
Total mass of the robot, in kilograms.

◆ eigen_from_bullet() [1/2]

Eigen::Quaterniond upkie::cpp::actuation::bullet::eigen_from_bullet ( const btQuaternion &  quat)
inline

Convert a Bullet quaternion to an Eigen one.

Parameters
[in]quatBullet quaternion.
Returns
Same vector for Eigen.

◆ eigen_from_bullet() [2/2]

Eigen::Vector3d upkie::cpp::actuation::bullet::eigen_from_bullet ( const btVector3 &  v)
inline

Convert a Bullet vector to an Eigen one.

Parameters
[in]vBullet vector.
Returns
Same vector for Eigen.

◆ find_link_index()

int upkie::cpp::actuation::bullet::find_link_index ( b3RobotSimulatorClientAPI &  bullet,
int  robot,
const std::string &  link_name 
)
inlinenoexcept

Find the index of a link.

Parameters
[in]bulletBullet client.
[in]robotIndex of the robot to search.
[in]link_nameName of the searched link.
Returns
Link index if found, -1 otherwise.

◆ get_position_link_in_world()

Eigen::Vector3d upkie::cpp::actuation::bullet::get_position_link_in_world ( b3RobotSimulatorClientAPI &  bullet,
int  robot,
int  link_index 
)
inlinenoexcept

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

Parameters
[in]bulletBullet client.
[in]robotIndex of the robot to search.
[in]link_indexIndex of the link frame.
Returns
Link index if found, -1 otherwise.
Note
This function will recompute forward kinematics.

◆ read_imu_data()

void upkie::cpp::actuation::bullet::read_imu_data ( ImuData imu_data,
b3RobotSimulatorClientAPI &  bullet,
int  robot,
const int  imu_link_index,
double  dt 
)
inline

Compute groundtruth IMU quantities from the IMU link state.

Parameters
[out]imu_dataIMU data to update.
[in]bulletBullet client.
[in]robotBullet index of the robot model.
[in]imu_link_indexIndex of the IMU link in the robot.
[in]dtSimulation timestep in [s].