C++ API and example

1. Introduction

This page exist in order to extract the examples from the Doxygen documentation, Please have look at the end of this page there are all the examples.

2. C++ API and example

class Args : public cli_utils::ProgramOptions

Public Functions

inline std::string help() const override
inline void add_options(boost::program_options::options_description &options, boost::program_options::positional_options_description &positional) override

Public Members

std::string config_file
float kp = 3.0
float kd = 0.05
class BaseBoltHumanoidDriver : public robot_interfaces::RobotDriver<BoltHumanoidAction, BoltHumanoidObservation>, public robot_interfaces::RobotDriver<BoltHumanoidAction, BoltHumanoidObservation>

Base class for BoltHumanoid drivers.

Subclassed by robot_interfaces_bolt::BoltHumanoidDriver, robot_interfaces_bolt::BoltHumanoidDriver, robot_interfaces_bolt::FakeBoltHumanoidDriver, robot_interfaces_bolt::FakeBoltHumanoidDriver, robot_interfaces_bolt::PyBulletBoltHumanoidDriver, robot_interfaces_bolt::PyBulletBoltHumanoidDriver

Public Types

typedef std::shared_ptr<BaseBoltHumanoidDriver> Ptr
typedef std::shared_ptr<const BaseBoltHumanoidDriver> ConstPtr
typedef std::shared_ptr<BaseBoltHumanoidDriver> Ptr
typedef std::shared_ptr<const BaseBoltHumanoidDriver> ConstPtr
struct BoltHumanoidAction : public robot_interfaces::Loggable, public robot_interfaces::Loggable

Action for the BoltHumanoid robot.

BoltHumanoid has an on-board PD+ controller which can be used by setting the P and D control gains per joint to the fields joint_position_gains and joint_velocity_gains. If the gains are zero, joint_positions and joint_velocities are ignored and only the torque commands in joint_torques are executed.

Public Functions

template<class Archive>
inline void serialize(Archive &archive)
inline std::vector<std::string> get_name() override
inline std::vector<std::vector<double>> get_data() override
template<class Archive>
inline void serialize(Archive &archive)
inline std::vector<std::string> get_name() override
inline std::vector<std::vector<double>> get_data() override

Public Members

Vector9d joint_torques = Vector9d::Zero()

Desired joint torques.

Vector9d joint_positions = Vector9d::Zero()

Desired joint positions.

Only used if joint_position_gains are set to a non-zero value.

Vector9d joint_velocities = Vector9d::Zero()

Desired joint velocities.

Only used if joint_velocity_gains are set to a non-zero value.

Vector9d joint_position_gains = Vector9d::Zero()

P-gains of the on-board PD+ controller.

Vector9d joint_velocity_gains = Vector9d::Zero()

D-gains of the on-board PD+ controller.

Public Static Functions

static inline BoltHumanoidAction Zero()

Create a zero-torque action.

This is equivalent to just using the default constructor but can be used to more explicitly show intend in the code.

static inline BoltHumanoidAction Zero()

Create a zero-torque action.

This is equivalent to just using the default constructor but can be used to more explicitly show intend in the code.

struct BoltHumanoidConfig

Configuration for the BoltHumanoid driver.

Public Members

std::string network_interface = ""

Name of the network interface to which the robot is connected (e.g.

“eth0”).

std::string slider_serial_port = ""

Name of the serial port to which the hardware slider is connected.

This can typically be left empty, in which case the port is auto-detected.

double max_motor_current_A = 8.0

Maximum current that can be applied to the motors (in Ampere).

Vector9d home_offset_rad = Vector9d::Zero()

Offset between home position (=encoder index) and zero position.

Angles (in radian) between the encoder index and the zero position of each joint.

std::string logger_level = "warning"

Logger output level.

One of {“trace”, “debug”, “info”, “warning”, “error”, “critical”, “off”}. See documentation of spdlog for details.

Public Static Functions

static BoltHumanoidConfig from_file(const std::filesystem::path &file)

Load configuration from a YAML file.

Parameters:

file – Path to the file

Returns:

Configuration instance. For parameters not provided in the file the default values are kept.

static BoltHumanoidConfig from_file(const std::filesystem::path &file)

Load configuration from a YAML file.

Parameters:

file – Path to the file

Returns:

Configuration instance. For parameters not provided in the file the default values are kept.

class BoltHumanoidDriver : public robot_interfaces_bolt::BaseBoltHumanoidDriver, public robot_interfaces_bolt::BaseBoltHumanoidDriver

Driver to use BoltHumanoid.

Public Functions

explicit BoltHumanoidDriver(const BoltHumanoidConfig &config)
void initialize() override
Action apply_action(const Action &desired_action) override
Observation get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override
explicit BoltHumanoidDriver(const BoltHumanoidConfig &config)
void initialize() override
Action apply_action(const Action &desired_action) override
Observation get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override

Public Static Attributes

static const std::string LOGGER_NAME = "BoltHumanoidDriver"

Private Members

std::shared_ptr<spdlog::logger> log_
const BoltHumanoidConfig config_
bolt::BoltHumanoid bolthumanoid_
Action applied_action_
bool is_initialized_ = false
struct BoltHumanoidObservation : public robot_interfaces::Loggable, public robot_interfaces::Loggable

Observation of the BoltHumanoid robot.

This observation class contains all the sensor data provided by the BoltHumanoid robot. The names of the attributes correspond to the names used in bolt::BoltHumanoid of the bolt package (for each attribute X, there is a method get_X()). See there for more information.

Public Functions

template<class Archive>
inline void serialize(Archive &archive)
inline std::vector<std::string> get_name() override
inline std::vector<std::vector<double>> get_data() override
template<class Archive>
inline void serialize(Archive &archive)
inline std::vector<std::string> get_name() override
inline std::vector<std::vector<double>> get_data() override

Public Members

Vector9d joint_positions

Measured joint positions.

Vector9d joint_velocities

Measured joint velocities.

Vector9d joint_torques

Measured joint torques.

Vector9d joint_target_torques

Target joint torques applied by the controller.

Eigen::Vector4d slider_positions

Positions of the hardware sliders, if connected (range: 0 to 1)

Eigen::Vector3d imu_accelerometer

Measurement of the IMU accelerometer.

Eigen::Vector3d imu_gyroscope

Measurement of the IMU gyroscope.

Eigen::Vector3d imu_linear_acceleration

Linear acceleration measured by the IMU.

Eigen::Vector4d imu_attitude

Attitude measured by the IMU.

class FakeBoltHumanoidDriver : public robot_interfaces_bolt::BaseBoltHumanoidDriver, public robot_interfaces_bolt::BaseBoltHumanoidDriver

Fake driver for testing (ignores actions and returns some artificial observations).

Public Functions

explicit FakeBoltHumanoidDriver(const BoltHumanoidConfig &config)
void initialize() override
Action apply_action(const Action &desired_action) override
Observation get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override
explicit FakeBoltHumanoidDriver(const BoltHumanoidConfig &config)
void initialize() override
Action apply_action(const Action &desired_action) override
Observation get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override

Public Static Attributes

static const std::string LOGGER_NAME = "FakeBoltHumanoidDriver"

Private Members

std::shared_ptr<spdlog::logger> log_
const BoltHumanoidConfig config_
Action applied_action_
bool is_initialized_ = false
double t_ = 0.0
class PyBulletBoltHumanoidDriver : public robot_interfaces_bolt::BaseBoltHumanoidDriver, public robot_interfaces_bolt::BaseBoltHumanoidDriver

Driver for BoltHumanoid in PyBullet simulation.

This driver can be used as a replacement for the “real” BoltHumanoid driver for testing things in simulation.

Warning

The fields imu_linear_acceleration and imu_attitude of the observation are not set by this driver, as the corresponding values are not provided by the simulation.

Public Functions

PyBulletBoltHumanoidDriver(bool real_time_mode = true, bool visualize = true, bool use_fixed_base = false, const std::string &logger_level = "debug")
Parameters:
  • real_time_mode – If true, sleep when stepping the simulation, so it runs in real time.

  • visualize – If true PyBullet’s visualisation is enabled (“GUI” mode), otherwise it is run in “DIRECT” mode without visualisation.

  • use_fixed_base – If true, the robot’s base is fixed and cannot move (i.e. the robot is hanging in the air). Can be useful for debugging.

  • logger_level – Output level used by the logger. Has to be a level supported by spdlog (e.g. “debug”, “info”, …). This is only considered if a new logger is initialised, i.e. the level is not changed, if a logger with the name stored in PyBulletBoltHumanoidDriver::LOGGER_NAME does already exist.

void initialize() override
BoltHumanoidObservation get_latest_observation() override
BoltHumanoidAction apply_action(const BoltHumanoidAction &desired_action) override
std::optional<std::string> get_error() override
void shutdown() override
py::object get_bullet_env()

Get the bullet environment instance for direct access to the simulation.

PyBulletBoltHumanoidDriver(bool real_time_mode = true, bool visualize = true, bool use_fixed_base = false, const std::string &logger_level = "debug")
Parameters:
  • real_time_mode – If true, sleep when stepping the simulation, so it runs in real time.

  • visualize – If true PyBullet’s visualisation is enabled (“GUI” mode), otherwise it is run in “DIRECT” mode without visualisation.

  • use_fixed_base – If true, the robot’s base is fixed and cannot move (i.e. the robot is hanging in the air). Can be useful for debugging.

  • logger_level – Output level used by the logger. Has to be a level supported by spdlog (e.g. “debug”, “info”, …). This is only considered if a new logger is initialised, i.e. the level is not changed, if a logger with the name stored in PyBulletBoltHumanoidDriver::LOGGER_NAME does already exist.

void initialize() override
BoltHumanoidObservation get_latest_observation() override
BoltHumanoidAction apply_action(const BoltHumanoidAction &desired_action) override
std::optional<std::string> get_error() override
void shutdown() override
py::object get_bullet_env()

Get the bullet environment instance for direct access to the simulation.

Public Static Attributes

static const std::string LOGGER_NAME = "PyBulletBoltHumanoidDriver"

Name of the spdlog logger used.

Private Functions

std::tuple<Vector9d, Vector9d> get_position_and_velocity()

Get tuple (joint_positions, joint_velocities).

std::tuple<Vector9d, Vector9d> get_position_and_velocity()

Get tuple (joint_positions, joint_velocities).

Private Members

std::shared_ptr<spdlog::logger> log_
bool real_time_mode_

If true, step simulation at 1 kHz, otherwise as fast as possible.

Vector9d desired_torques_ = Vector9d::Zero()

The torque-part of the last desired action.

Vector9d applied_torques_ = Vector9d::Zero()

Actual torques that were applied based on the latest action.

This also includes the resulting torque from the PD controller if the corresponding parts of the action were set.

py::object sim_env_

Instance of bullet_utils.env.BulletEnvWithGround used to set up the simulation.

py::object sim_robot_

Instance of robot_properties_bolt.bolthumanoidwrapper.BoltHumanoidRobot for controlling the simulated robot.

namespace cli_utils
namespace robot_interfaces
namespace robot_interfaces_bolt

Typedefs

typedef Eigen::Matrix<double, 9, 1> Vector9d
typedef robot_interfaces::RobotBackend<BoltHumanoidAction, BoltHumanoidObservation> BoltHumanoidBackend
typedef robot_interfaces::RobotFrontend<BoltHumanoidAction, BoltHumanoidObservation> BoltHumanoidFrontend
typedef robot_interfaces::RobotData<BoltHumanoidAction, BoltHumanoidObservation> BoltHumanoidData
typedef robot_interfaces::SingleProcessRobotData<BoltHumanoidAction, BoltHumanoidObservation> BoltHumanoidSingleProcessData
typedef robot_interfaces::MultiProcessRobotData<BoltHumanoidAction, BoltHumanoidObservation> BoltHumanoidMultiProcessData

Functions

BoltHumanoidBackend::Ptr create_real_bolthumanoid_backend(BoltHumanoidData::Ptr robot_data, const BoltHumanoidConfig &driver_config, const double first_action_timeout = std::numeric_limits<double>::infinity(), const uint32_t max_number_of_actions = 0)

Create robot backend using the BoltHumanoid driver (real robot).

Parameters:
  • robot_data – Instance of RobotData used for communication.

  • driver_config – Driver configuration.

  • first_action_timeout – Duration for which the backend waits for the first action to arrive. If exceeded, the backend shuts down.

  • max_number_of_actions – Number of actions after which the backend automatically shuts down.

Returns:

A RobotBackend instances which uses a BoltHumanoid driver.

BoltHumanoidBackend::Ptr create_fake_bolthumanoid_backend(BoltHumanoidData::Ptr robot_data, const BoltHumanoidConfig &driver_config, const double first_action_timeout = std::numeric_limits<double>::infinity(), const uint32_t max_number_of_actions = 0)

Create robot backend using the fake BoltHumanoid driver (for testing).

Arguments are the same as for create_real_bolthumanoid_backend.

BoltHumanoidBackend::Ptr create_pybullet_bolthumanoid_backend(BoltHumanoidData::Ptr robot_data, const BoltHumanoidConfig &driver_config, const double first_action_timeout = std::numeric_limits<double>::infinity(), const uint32_t max_number_of_actions = 0)

Create robot backend using the PyBullet BoltHumanoid driver (for testing).

Arguments are the same as for create_real_bolthumanoid_backend.

This function uses default values for initialising the simulation driver. If you want more control over the settings (including direct access to the simulation environment), create a driver instance yourself and use create_bolthumanoid_backend.

BoltHumanoidBackend::Ptr create_bolthumanoid_backend(BoltHumanoidData::Ptr robot_data, BaseBoltHumanoidDriver::Ptr robot_driver, const double first_action_timeout = std::numeric_limits<double>::infinity(), const uint32_t max_number_of_actions = 0, bool enable_timing_watchdog = true)

Create robot backend using a BoltHumanoid driver.

Parameters:
  • robot_data – Instance of RobotData used for communication.

  • robot_driver – Driver instance, connecting to the robot or simulation.

  • first_action_timeout – Duration for which the backend waits for the first action to arrive. If exceeded, the backend shuts down.

  • max_number_of_actions – Number of actions after which the backend automatically shuts down.

  • enable_timing_watchdog – Whether to enable the backend timing watchdog (triggers an error if real-time constraints of the backend are violated). This should enabled if using the real robot but may be disabled when using simulation.

Returns:

A RobotBackend instances which uses a BoltHumanoid driver.

file tmp-cxx-standard.cpp
#include <iostream>

Functions

int main()
file CMakeCCompilerId.c

Defines

__has_include(x)
COMPILER_ID
STRINGIFY_HELPER(X)
STRINGIFY(X)
PLATFORM_ID
ARCHITECTURE_ID
DEC(n)
HEX(n)
C_VERSION

Functions

int main(int argc, char *argv[])

Variables

char const  * info_compiler   = "INFO" ":" "compiler[" COMPILER_ID "]"
char const  * info_platform   = "INFO" ":" "platform[" PLATFORM_ID "]"
char const  * info_arch   = "INFO" ":" "arch[" ARCHITECTURE_ID "]"
const char * info_language_standard_default  ="INFO" ":" "standard_default[" C_VERSION "]"
const char * info_language_extensions_default  = "INFO" ":" "extensions_default[""OFF""]"
file CMakeCXXCompilerId.cpp

Defines

__has_include(x)
COMPILER_ID
STRINGIFY_HELPER(X)
STRINGIFY(X)
PLATFORM_ID
ARCHITECTURE_ID
DEC(n)
HEX(n)
CXX_STD

Functions

int main(int argc, char *argv[])

Variables

char const  * info_compiler   = "INFO" ":" "compiler[" COMPILER_ID "]"
char const  * info_platform   = "INFO" ":" "platform[" PLATFORM_ID "]"
char const  * info_arch   = "INFO" ":" "arch[" ARCHITECTURE_ID "]"
const char * info_language_standard_default  = "INFO" ":" "standard_default[""98""]"
const char * info_language_extensions_default  = "INFO" ":" "extensions_default[""OFF""]"
file demo_bolthumanoid_hold.cpp
#include <memory>
#include <string>
#include <cli_utils/program_options.hpp>
#include <robot_interfaces_bolt/bolthumanoid_driver.hpp>

Demo using BoltHumanoid that holds all joints at their current positions.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

Functions

int main(int argc, char *argv[])
file basic_types.hpp
#include <Eigen/Eigen>

Some rather generic type definitions.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file basic_types.hpp
#include <Eigen/Eigen>

Some rather generic type definitions.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_action.hpp
#include <string>
#include <vector>
#include <Eigen/Eigen>
#include <cereal/cereal.hpp>
#include <serialization_utils/cereal_eigen.hpp>
#include <robot_interfaces/loggable.hpp>
#include “basic_types.hpp

Action for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_action.hpp
#include <string>
#include <vector>
#include <Eigen/Eigen>
#include <cereal/cereal.hpp>
#include <serialization_utils/cereal_eigen.hpp>
#include <robot_interfaces/loggable.hpp>
#include “basic_types.hpp

Action for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_config.hpp
#include <filesystem>
#include “basic_types.hpp

Config for BoltHumanoid drivers.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_config.hpp
#include <filesystem>
#include “basic_types.hpp

Config for BoltHumanoid drivers.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_driver.hpp
#include <filesystem>
#include <limits>
#include <memory>
#include <string>
#include <spdlog/spdlog.h>
#include <bolt/bolt_humanoid.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “bolthumanoid_types.hpp

Driver for using BoltHumanoid in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_driver.hpp
#include <filesystem>
#include <limits>
#include <memory>
#include <string>
#include <spdlog/spdlog.h>
#include <bolt/bolt_humanoid.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “bolthumanoid_types.hpp

Driver for using BoltHumanoid in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_observation.hpp
#include <cstdint>
#include <string>
#include <vector>
#include <Eigen/Eigen>
#include <cereal/cereal.hpp>
#include <serialization_utils/cereal_eigen.hpp>
#include <robot_interfaces/loggable.hpp>
#include “basic_types.hpp

Observation for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_observation.hpp
#include <cstdint>
#include <string>
#include <vector>
#include <Eigen/Eigen>
#include <cereal/cereal.hpp>
#include <serialization_utils/cereal_eigen.hpp>
#include <robot_interfaces/loggable.hpp>
#include “basic_types.hpp

Observation for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_pybullet_driver.hpp
#include <pybind11/pybind11.h>
#include <spdlog/spdlog.h>
#include <robot_interfaces/robot_driver.hpp>
#include “bolthumanoid_types.hpp

Driver for using simulated BoltHumanoid in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_pybullet_driver.hpp
#include <pybind11/pybind11.h>
#include <spdlog/spdlog.h>
#include <robot_interfaces/robot_driver.hpp>
#include “bolthumanoid_types.hpp

Driver for using simulated BoltHumanoid in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_types.hpp
#include <memory>
#include <robot_interfaces/robot_backend.hpp>
#include <robot_interfaces/robot_data.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “bolthumanoid_action.hpp
#include “bolthumanoid_config.hpp

robot_interfaces types for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_types.hpp
#include <memory>
#include <robot_interfaces/robot_backend.hpp>
#include <robot_interfaces/robot_data.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “bolthumanoid_action.hpp
#include “bolthumanoid_config.hpp

robot_interfaces types for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_utils.hpp
#include <limits>
#include “bolthumanoid_types.hpp

Utility functions for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid_utils.hpp
#include <limits>
#include “bolthumanoid_types.hpp

Utility functions for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file bolthumanoid.cpp
#include <limits>
#include <memory>
#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <pybind11/stl/filesystem.h>
#include <robot_interfaces/pybind_helper.hpp>
#include <robot_interfaces_bolt/bolthumanoid_driver.hpp>
#include <robot_interfaces_bolt/bolthumanoid_pybullet_driver.hpp>
#include <robot_interfaces_bolt/bolthumanoid_utils.hpp>

Python bindings for BoltHumanoid.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

Functions

PYBIND11_MODULE(bolthumanoid, m)
dir build/robot_interfaces_bolt/CMakeFiles/3.22.1
dir build
dir build/robot_interfaces_bolt/cmake
dir build/robot_interfaces_bolt/CMakeFiles
dir build/robot_interfaces_bolt/CMakeFiles/3.22.1/CompilerIdC
dir build/robot_interfaces_bolt/CMakeFiles/3.22.1/CompilerIdCXX
dir demos
dir include
dir install/robot_interfaces_bolt/include
dir install
dir build/robot_interfaces_bolt
dir include/robot_interfaces_bolt
dir install/robot_interfaces_bolt
dir install/robot_interfaces_bolt/include/robot_interfaces_bolt
dir srcpy