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

template<int X>
class _BaseSoloXDriver : public robot_interfaces::RobotDriver<_SoloXAction<X>, _SoloXObservation<X>>, public robot_interfaces::RobotDriver<_SoloXAction<X>, _SoloXObservation<X>>
#include <solo_types.hpp>

Base class for Solo drivers.

Subclassed by robot_interfaces_solo::_FakeSoloXDriver< X >, robot_interfaces_solo::_FakeSoloXDriver< X >, robot_interfaces_solo::_PyBulletSoloXDriver< X >, robot_interfaces_solo::_PyBulletSoloXDriver< X >, robot_interfaces_solo::_SoloXDriver< X, SoloInterface >, robot_interfaces_solo::_SoloXDriver< X, SoloInterface >

Public Types

typedef std::shared_ptr<_BaseSoloXDriver<X>> Ptr
typedef std::shared_ptr<const _BaseSoloXDriver<X>> ConstPtr
typedef std::shared_ptr<_BaseSoloXDriver<X>> Ptr
typedef std::shared_ptr<const _BaseSoloXDriver<X>> ConstPtr
template<int X>
class _FakeSoloXDriver : public robot_interfaces_solo::_BaseSoloXDriver<X>, public robot_interfaces_solo::_BaseSoloXDriver<X>
#include <solo_driver.hpp>

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

Public Functions

explicit _FakeSoloXDriver(const _SoloXConfig<X> &config)
void initialize() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &desired_action) override
_SoloXObservation<X> get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override
explicit _FakeSoloXDriver(const _SoloXConfig<X> &config)
void initialize() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &desired_action) override
_SoloXObservation<X> get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override

Public Static Attributes

static const std::string LOGGER_NAME = "FakeSoloDriver"

Private Members

std::shared_ptr<spdlog::logger> log_
const _SoloXConfig<X> config_
_SoloXAction<X> applied_action_
bool is_initialized_ = false
double t_ = 0.0
template<int X>
class _PyBulletSoloXDriver : public robot_interfaces_solo::_BaseSoloXDriver<X>, public robot_interfaces_solo::_BaseSoloXDriver<X>

Driver for Solo in PyBullet simulation.

This driver can be used as a replacement for the “real” Solo 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

_PyBulletSoloXDriver(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 LOGGER_NAME does already exist.

void initialize() override
_SoloXObservation<X> get_latest_observation() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &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.

_PyBulletSoloXDriver(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 LOGGER_NAME does already exist.

void initialize() override
_SoloXObservation<X> get_latest_observation() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &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 = "PyBulletSoloDriver"

Name of the spdlog logger used.

Private Functions

std::tuple<Vector<X>, Vector<X>> get_position_and_velocity()

Get tuple (joint_positions, joint_velocities).

std::tuple<Vector<X>, Vector<X>> 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.

int command_packet_counter_ = 0

Number of received commands (=actions).

int sensor_packet_counter_ = 0

Number of provided observations.

Vector<X> desired_torques_ = Vector<X>::Zero()

The torque-part of the last desired action.

Vector<X> applied_torques_ = Vector<X>::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_solo.soloXwrapper.SoloXRobot for controlling the simulated robot.

template<int X>
struct _SoloXAction : public robot_interfaces::Loggable, public robot_interfaces::Loggable
#include <solo_action.hpp>

Action for the Solo robot.

Solo 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

Vector<X> joint_torques = Vector<X>::Zero()

Desired joint torques.

Vector<X> joint_positions = Vector<X>::Zero()

Desired joint positions.

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

Vector<X> joint_velocities = Vector<X>::Zero()

Desired joint velocities.

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

Vector<X> joint_position_gains = Vector<X>::Zero()

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

Vector<X> joint_velocity_gains = Vector<X>::Zero()

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

Public Static Functions

static inline _SoloXAction<X> 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 _SoloXAction<X> 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.

template<int X>
struct _SoloXConfig
#include <solo_config.hpp>

Configuration for a SoloX robot using the master board.

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).

Vector<X> home_offset_rad = Vector<X>::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 _SoloXConfig<X> 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 _SoloXConfig<X> 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.

template<int X, typename SoloInterface>
class _SoloXDriver : public robot_interfaces_solo::_BaseSoloXDriver<X>, public robot_interfaces_solo::_BaseSoloXDriver<X>
#include <solo_driver.hpp>

Driver to use Solo with master board.

Public Functions

explicit _SoloXDriver(const _SoloXConfig<X> &config)
void initialize() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &desired_action) override
_SoloXObservation<X> get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override
explicit _SoloXDriver(const _SoloXConfig<X> &config)
void initialize() override
_SoloXAction<X> apply_action(const _SoloXAction<X> &desired_action) override
_SoloXObservation<X> get_latest_observation() override
std::optional<std::string> get_error() override
void shutdown() override

Public Static Attributes

static const std::string LOGGER_NAME = "SoloDriver"

Private Members

std::shared_ptr<spdlog::logger> log_
const _SoloXConfig<X> config_
SoloInterface solo_
_SoloXAction<X> applied_action_
bool is_initialized_ = false
template<int X>
struct _SoloXObservation : public robot_interfaces::Loggable, public robot_interfaces::Loggable

Observation of the Solo robot.

This observation class contains all the sensor data provided by the Solo robot. The names of the attributes correspond to the names used in solo::Solo12 of the solo 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

Vector<X> joint_positions

Measured joint positions.

Vector<X> joint_velocities

Measured joint velocities.

Vector<X> joint_torques

Measured joint torques.

Vector<X> joint_target_torques

Target joint torques applied by the controller.

Vector<X> joint_encoder_index

Currently not set!

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.

uint32_t num_sent_command_packets

Total number of command packets sent to the robot.

uint32_t num_lost_command_packets

Number of command packets that were sent to the robot but were lost in transmission.

uint32_t num_sent_sensor_packets

Total number of sensor packets sent from the robot.

uint32_t num_lost_sensor_packets

Number of sensor packets that were sent from the robot but were lost in transmission.

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
namespace cli_utils
namespace robot_interfaces
namespace robot_interfaces_solo

Typedefs

template<int X>
using Vector = Eigen::Matrix<double, X, 1>
typedef _SoloXAction<8> Solo8Action
typedef _SoloXAction<12> Solo12Action
typedef _SoloXConfig<8> Solo8Config

Configuration for the Solo8 driver.

typedef _SoloXConfig<12> Solo12Config

Configuration for the Solo12 driver.

typedef _SoloXDriver<8, solo::Solo8> Solo8Driver
typedef _SoloXDriver<12, solo::Solo12> Solo12Driver
typedef _FakeSoloXDriver<8> FakeSolo8Driver
typedef _FakeSoloXDriver<12> FakeSolo12Driver
typedef _SoloXObservation<8> Solo8Observation
typedef _SoloXObservation<12> Solo12Observation
typedef _PyBulletSoloXDriver<8> PyBulletSolo8Driver
typedef _PyBulletSoloXDriver<12> PyBulletSolo12Driver
typedef _BaseSoloXDriver<8> BaseSolo8Driver
typedef robot_interfaces::RobotBackend<Solo8Action, Solo8Observation> Solo8Backend
typedef robot_interfaces::RobotFrontend<Solo8Action, Solo8Observation> Solo8Frontend
typedef robot_interfaces::RobotData<Solo8Action, Solo8Observation> Solo8Data
typedef robot_interfaces::SingleProcessRobotData<Solo8Action, Solo8Observation> Solo8SingleProcessData
typedef robot_interfaces::MultiProcessRobotData<Solo8Action, Solo8Observation> Solo8MultiProcessData
typedef _BaseSoloXDriver<12> BaseSolo12Driver
typedef robot_interfaces::RobotBackend<Solo12Action, Solo12Observation> Solo12Backend
typedef robot_interfaces::RobotFrontend<Solo12Action, Solo12Observation> Solo12Frontend
typedef robot_interfaces::RobotData<Solo12Action, Solo12Observation> Solo12Data
typedef robot_interfaces::SingleProcessRobotData<Solo12Action, Solo12Observation> Solo12SingleProcessData
typedef robot_interfaces::MultiProcessRobotData<Solo12Action, Solo12Observation> Solo12MultiProcessData

Functions

template<typename T>
void _set_optional_config_value(const YAML::Node &user_config, const std::string &name, T *var)
Solo12Backend::Ptr create_real_solo12_backend(Solo12Data::Ptr robot_data, const Solo12Config &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 Solo12 driver (real robot).

See also

Solo12Driver

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 Solo12 driver.

Solo12Backend::Ptr create_fake_solo12_backend(Solo12Data::Ptr robot_data, const Solo12Config &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 Solo12 driver (for testing).

Arguments are the same as for create_real_solo12_backend.

See also

FakeSolo12Driver

Solo8Backend::Ptr create_real_solo8_backend(Solo8Data::Ptr robot_data, const Solo8Config &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 Solo8 driver (real robot).

See also

Solo8Driver

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 Solo8 driver.

Solo8Backend::Ptr create_fake_solo8_backend(Solo8Data::Ptr robot_data, const Solo8Config &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 Solo8 driver (for testing).

Arguments are the same as for create_real_solo8_backend.

See also

FakeSolo8Driver

Solo8Backend::Ptr create_pybullet_solo8_backend(Solo8Data::Ptr robot_data, const Solo8Config &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 Solo8 driver (for testing).

Arguments are the same as for create_real_solo8_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_solo8_backend.

Solo12Backend::Ptr create_pybullet_solo12_backend(Solo12Data::Ptr robot_data, const Solo12Config &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 Solo12 driver (for testing).

Arguments are the same as for create_real_solo12_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_solo12_backend.

template<typename Backend, typename Data, typename Driver, typename Action, typename Observation>
Backend::Ptr create_solox_backend(typename Data::Ptr robot_data, typename Driver::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 SoloX 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 Solo12 driver.

Solo8Backend::Ptr create_solo8_backend(Solo8Data::Ptr robot_data, BaseSolo8Driver::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)

Specialisation of create_solox_backend for Solo8.

Solo12Backend::Ptr create_solo12_backend(Solo12Data::Ptr robot_data, BaseSolo12Driver::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)

Specialisation of create_solox_backend for Solo12.

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_solo12_hold.cpp
#include <memory>
#include <string>
#include <cli_utils/program_options.hpp>
#include <robot_interfaces_solo/solo_driver.hpp>

Demo using Solo12 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 solo_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 Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_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 Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_config.hpp
#include <filesystem>
#include <fmt/format.h>
#include <yaml-cpp/yaml.h>
#include <yaml_utils/yaml_eigen.hpp>
#include “basic_types.hpp

Config for Solo12 drivers.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_config.hpp
#include <filesystem>
#include <fmt/format.h>
#include <yaml-cpp/yaml.h>
#include <yaml_utils/yaml_eigen.hpp>
#include “basic_types.hpp

Config for Solo12 drivers.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_driver.hpp
#include <filesystem>
#include <limits>
#include <memory>
#include <string>
#include <spdlog/sinks/stdout_color_sinks.h>
#include <spdlog/spdlog.h>
#include <boost/range/adaptor/indexed.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include <solo/solo12.hpp>
#include <solo/solo8.hpp>
#include “solo_types.hpp

Driver for using Solo in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_driver.hpp
#include <filesystem>
#include <limits>
#include <memory>
#include <string>
#include <spdlog/sinks/stdout_color_sinks.h>
#include <spdlog/spdlog.h>
#include <boost/range/adaptor/indexed.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include <solo/solo12.hpp>
#include <solo/solo8.hpp>
#include “solo_types.hpp

Driver for using Solo in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_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 Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_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 Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_pybullet_driver.hpp
#include <fmt/format.h>
#include <pybind11/pybind11.h>
#include <spdlog/sinks/stdout_color_sinks.h>
#include <spdlog/spdlog.h>
#include <robot_interfaces/robot_driver.hpp>
#include “solo_types.hpp

Driver for using simulated Solo in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_pybullet_driver.hpp
#include <fmt/format.h>
#include <pybind11/pybind11.h>
#include <spdlog/sinks/stdout_color_sinks.h>
#include <spdlog/spdlog.h>
#include <robot_interfaces/robot_driver.hpp>
#include “solo_types.hpp

Driver for using simulated Solo in robot_interfaces::RobotBackend.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_types.hpp
#include <memory>
#include <robot_interfaces/robot_backend.hpp>
#include <robot_interfaces/robot_data.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “solo_action.hpp
#include “solo_config.hpp
#include “solo_observation.hpp

robot_interfaces types for Solo8 and Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_types.hpp
#include <memory>
#include <robot_interfaces/robot_backend.hpp>
#include <robot_interfaces/robot_data.hpp>
#include <robot_interfaces/robot_frontend.hpp>
#include “solo_action.hpp
#include “solo_config.hpp
#include “solo_observation.hpp

robot_interfaces types for Solo8 and Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_utils.hpp
#include <limits>
#include <memory>
#include <robot_interfaces/monitored_robot_driver.hpp>
#include “solo_types.hpp

Utility functions for Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo_utils.hpp
#include <limits>
#include <memory>
#include <robot_interfaces/monitored_robot_driver.hpp>
#include “solo_types.hpp

Utility functions for Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

file solo12.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_solo/solo_driver.hpp>
#include <robot_interfaces_solo/solo_pybullet_driver.hpp>
#include <robot_interfaces_solo/solo_utils.hpp>

Python bindings for Solo12.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

Functions

PYBIND11_MODULE(solo12, m)
file solo8.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_solo/solo_driver.hpp>
#include <robot_interfaces_solo/solo_pybullet_driver.hpp>
#include <robot_interfaces_solo/solo_utils.hpp>

Python bindings for Solo8.

Copyright

Copyright (c) 2022, Max Planck Gesellschaft.

Functions

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