vulp  2.3.0
vulp::actuation Namespace Reference

Send actions to actuators or simulators. More...

Namespaces

 default_action
 

Classes

struct  BulletContactData
 Contact information for a single link. More...
 
struct  BulletImuData
 
class  BulletInterface
 Actuation interface for the Bullet simulator. More...
 
struct  BulletJointProperties
 Properties for robot joints in the Bullet simulation. More...
 
struct  ImuData
 Data filtered from an onboard IMU such as the pi3hat's. More...
 
class  Interface
 Base class for actuation interfaces. More...
 
class  MockInterface
 
class  Pi3HatInterface
 Interface to moteus controllers. More...
 
class  ServoLayout
 Map between servos, their busses and the joints they actuate. More...
 

Typedefs

using Pi3Hat = ::mjbots::pi3hat::Pi3Hat
 

Functions

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...
 
void read_imu_data (BulletImuData &imu_data, b3RobotSimulatorClientAPI &bullet, int robot, const int imu_link_index, double dt)
 Compute IMU readings from the IMU link state. More...
 
std::string find_plane_urdf (const std::string argv0)
 
actuation::moteus::QueryCommand get_query_resolution ()
 Query resolution settings for all servo commands. More...
 
actuation::moteus::PositionResolution get_position_resolution ()
 Resolution settings for all servo commands. More...
 

Detailed Description

Send actions to actuators or simulators.

Typedef Documentation

◆ Pi3Hat

using vulp::actuation::Pi3Hat = typedef ::mjbots::pi3hat::Pi3Hat

Definition at line 36 of file Pi3HatInterface.h.

Function Documentation

◆ bullet_from_eigen() [1/2]

btQuaternion vulp::actuation::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.

Definition at line 21 of file bullet_utils.h.

◆ bullet_from_eigen() [2/2]

btVector3 vulp::actuation::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.

Definition at line 31 of file bullet_utils.h.

◆ eigen_from_bullet() [1/2]

Eigen::Quaterniond vulp::actuation::eigen_from_bullet ( const btQuaternion &  quat)
inline

Convert a Bullet quaternion to an Eigen one.

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

Definition at line 41 of file bullet_utils.h.

◆ eigen_from_bullet() [2/2]

Eigen::Vector3d vulp::actuation::eigen_from_bullet ( const btVector3 &  v)
inline

Convert a Bullet vector to an Eigen one.

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

Definition at line 51 of file bullet_utils.h.

◆ find_link_index()

int vulp::actuation::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.

Definition at line 63 of file bullet_utils.h.

◆ find_plane_urdf()

std::string vulp::actuation::find_plane_urdf ( const std::string  argv0)

Definition at line 17 of file BulletInterface.cpp.

◆ get_position_resolution()

actuation::moteus::PositionResolution vulp::actuation::get_position_resolution ( )
inline

Resolution settings for all servo commands.

Returns
Resolution settings.

For now these settings are common to all interfaces but we can easily turn them into parameters.

Definition at line 41 of file resolution.h.

◆ get_query_resolution()

actuation::moteus::QueryCommand vulp::actuation::get_query_resolution ( )
inline

Query resolution settings for all servo commands.

Returns
Query resolution settings.

For now these settings are common to all interfaces but we can easily turn them into parameters.

Definition at line 18 of file resolution.h.

◆ read_imu_data()

void vulp::actuation::read_imu_data ( BulletImuData imu_data,
b3RobotSimulatorClientAPI &  bullet,
int  robot,
const int  imu_link_index,
double  dt 
)
inline

Compute IMU readings 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].

Definition at line 84 of file bullet_utils.h.