|
upkie 10.0.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... | |
| double | dt = std::numeric_limits<double>::quiet_NaN() |
| Simulation timestep in [s]. | |
| bool | follower_camera = false |
| Translate the camera to follow the robot. | |
| 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, double > | model_maximum_torque |
| Maximum torque limits per joint read from model. | |
| ImuUncertainty | imu_uncertainty |
| Uncertainty on IMU measurements. | |
| Eigen::VectorXd | joint_configuration |
| Initial joint configuration vector. | |
Interface parameters.