vulp
2.3.0
|
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 ¶ms) | |
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 ServoLayout & | servo_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... | |
Actuation interface for the Bullet simulator.
Definition at line 25 of file BulletInterface.h.
vulp::actuation::BulletInterface::BulletInterface | ( | const ServoLayout & | layout, |
const Parameters & | params | ||
) |
Initialize interface.
[in] | layout | Servo layout. |
[in] | params | Interface parameters. |
std::runtime_error | If the simulator did not start properly. |
Definition at line 27 of file BulletInterface.cpp.
vulp::actuation::BulletInterface::~BulletInterface | ( | ) |
Disconnect interface.
Definition at line 108 of file BulletInterface.cpp.
|
noexcept |
Get the groundtruth floating base angular velocity.
Definition at line 334 of file BulletInterface.cpp.
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.
[in] | joint_name | Name of the joint. |
[in] | feedforward_torque | Feedforward torque command in [N] * [m]. |
[in] | target_position | Target angular position in [rad]. |
[in] | target_velocity | Target angular velocity in [rad] / [s]. |
[in] | kp_scale | Multiplicative factor applied to the proportional gain in torque control. |
[in] | kd_scale | Multiplicative factor applied to the derivative gain in torque control. |
[in] | maximum_torque | Maximum torque in [N] * [m] from the command. |
Definition at line 289 of file BulletInterface.cpp.
|
finalvirtual |
Spin a new communication cycle.
data | Buffer to read commands from and write replies to. |
callback | Function 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.
|
inline |
Joint properties (accessor used for testing)
Definition at line 243 of file BulletInterface.h.
|
noexcept |
Get the groundtruth floating base linear velocity.
Definition at line 326 of file BulletInterface.cpp.
|
overridevirtual |
Write actuation-interface observations to dictionary.
[out] | observation | Dictionary to write ot. |
Implements vulp::actuation::Interface.
Definition at line 170 of file BulletInterface.cpp.
|
overridevirtual |
Reset interface.
[in] | config | Additional configuration dictionary. |
Implements vulp::actuation::Interface.
Definition at line 110 of file BulletInterface.cpp.
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.
[in] | position_base_in_world | Position of the base in the world frame. |
[in] | orientation_base_in_world | Orientation of the base in the world frame. |
[in] | linear_velocity_base_to_world_in_world | Linear velocity of the base in the world frame. |
[in] | angular_velocity_base_in_base | Body angular velocity of the base (in the base frame). |
Definition at line 122 of file BulletInterface.cpp.
void vulp::actuation::BulletInterface::reset_contact_data | ( | ) |
Reset contact data.
Definition at line 140 of file BulletInterface.cpp.
void vulp::actuation::BulletInterface::reset_joint_angles | ( | ) |
Reset joint angles to zero.
Definition at line 146 of file BulletInterface.cpp.
void vulp::actuation::BulletInterface::reset_joint_properties | ( | ) |
Reset joint properties to defaults.
Definition at line 153 of file BulletInterface.cpp.
|
inline |
Internal map of servo replies (accessor used for testing)
Definition at line 248 of file BulletInterface.h.
|
noexcept |
Get the groundtruth floating base transform.
Definition at line 314 of file BulletInterface.cpp.