upkie 6.1.0
Open-source wheeled biped robots
|
#include <BulletInterface.h>
Public Member Functions | |
Parameters ()=default | |
Keep default constructor. | |
Parameters (const Dictionary &config) | |
Initialize from global configuration. More... | |
void | configure (const Dictionary &config) |
Configure from dictionary. More... | |
Public Attributes | |
std::string | argv0 = "" |
Value of argv[0] used to locate runfiles (e.g. More... | |
std::map< std::string, std::map< std::string, std::vector< std::string > > > | monitor_contacts |
Contacts to monitor and report along with observations. | |
double | dt = std::numeric_limits<double>::quiet_NaN() |
Simulation timestep in [s]. | |
bool | follower_camera = false |
Translate the camera to follow the robot. | |
double | inertia_randomization = 0.0 |
Mass randomization epsilon. | |
bool | gravity = true |
If true, set gravity to -9.81 m/s². | |
bool | floor = true |
If true, load a floor plane. | |
bool | gui = false |
If true, fire up the graphical user interface. | |
std::string | robot_urdf_path |
Path to the URDF model of the robot. More... | |
std::vector< std::string > | env_urdf_paths |
Paths to environment URDFs to load. | |
double | torque_control_kd = 1.0 |
Gain for joint velocity control feedback. | |
double | torque_control_kp = 20.0 |
Gain for joint position control feedback. | |
Eigen::Vector3d | position_base_in_world = Eigen::Vector3d::Zero() |
Position of the base in the world frame upon reset. | |
Eigen::Quaterniond | orientation_base_in_world |
Orientation of the base in the world frame upon reset. More... | |
Eigen::Vector3d | linear_velocity_base_to_world_in_world |
Linear velocity of the base in the world frame upon reset. More... | |
Eigen::Vector3d | angular_velocity_base_in_base = Eigen::Vector3d::Zero() |
Body angular velocity of the base upon reset. | |
std::map< std::string, bullet::JointProperties > | joint_properties |
Joint friction parameters. | |
ImuUncertainty | imu_uncertainty |
Uncertainty on IMU measurements. | |
Eigen::VectorXd | joint_configuration |
Initial joint configuration vector. | |
Interface parameters.
|
inlineexplicit |
Initialize from global configuration.
[in] | config | Global configuration dictionary. |
|
inline |
Configure from dictionary.
[in] | config | Global configuration dictionary. |
std::string upkie::cpp::actuation::BulletInterface::Parameters::argv0 = "" |
Value of argv[0] used to locate runfiles (e.g.
plane.urdf) in Bazel.
This value helps find runfiles because Bazel does not seem to set the RUNFILES_MANIFEST_FILE environment variable from cc_binary rules, although in a similar context it does set it from py_binary rules that depend on "@rules_python//python/runfiles". When RUNFILES_MANIFEST_FILE is unset, knowing argv[0] triggers an alternative way to find runfiles.
The following issues are related:
https://github.com/bazelbuild/bazel/issues/4586 https://github.com/bazelbuild/bazel/issues/7994
Eigen::Vector3d upkie::cpp::actuation::BulletInterface::Parameters::linear_velocity_base_to_world_in_world |
Linear velocity of the base in the world frame upon reset.
Eigen::Quaterniond upkie::cpp::actuation::BulletInterface::Parameters::orientation_base_in_world |
Orientation of the base in the world frame upon reset.
std::string upkie::cpp::actuation::BulletInterface::Parameters::robot_urdf_path |
Path to the URDF model of the robot.
A path from the root of the Bazel workspace works. For instance, use "models/upkie_description/urdf/upkie.urdf" to load the URDF from Bazel data such as data = ["//models/upkie_description"]
.
For external targets, add the "external/" prefix. For instance, use "external/upkie_description/urdf/upkie.urdf" to load the URDF from Bazel data loaded from a dependency: data = ["@upkie_description"]
.