Namespace robot_interfaces¶
-
namespace robot_interfaces¶
Typedefs
-
typedef FingerTypes<1> MonoFingerTypes¶
-
typedef FingerTypes<3> TriFingerTypes¶
-
typedef time_series::Index TimeIndex¶
Enums
-
enum RobotBackendTerminationReason¶
Possible termination reasons of a RobotBackend.
Values:
-
enumerator NOT_TERMINATED¶
Backend is still running.
-
enumerator SHUTDOWN_REQUESTED¶
Shutdown requested for non-failure reason (e.g. by SIGINT).
-
enumerator MAXIMUM_NUMBER_OF_ACTIONS_REACHED¶
Maximum number of actions was reached.
-
enumerator DRIVER_ERROR¶
Some error in the driver.
-
enumerator FIRST_ACTION_TIMEOUT¶
First action timeout was triggered.
-
enumerator NEXT_ACTION_TIMEOUT¶
Next action timeout was triggered.
-
enumerator NOT_TERMINATED
Backend is still running.
-
enumerator SHUTDOWN_REQUESTED
Shutdown requested for non-failure reason (e.g. by SIGINT).
-
enumerator MAXIMUM_NUMBER_OF_ACTIONS_REACHED
Maximum number of actions was reached.
-
enumerator DRIVER_ERROR
Some error in the driver.
-
enumerator FIRST_ACTION_TIMEOUT
First action timeout was triggered.
-
enumerator NEXT_ACTION_TIMEOUT
Next action timeout was triggered.
-
enumerator NOT_TERMINATED¶
-
enum RobotBackendTerminationReason
Possible termination reasons of a RobotBackend.
Values:
-
enumerator NOT_TERMINATED
Backend is still running.
-
enumerator SHUTDOWN_REQUESTED
Shutdown requested for non-failure reason (e.g. by SIGINT).
-
enumerator MAXIMUM_NUMBER_OF_ACTIONS_REACHED
Maximum number of actions was reached.
-
enumerator DRIVER_ERROR
Some error in the driver.
-
enumerator FIRST_ACTION_TIMEOUT
First action timeout was triggered.
-
enumerator NEXT_ACTION_TIMEOUT
Next action timeout was triggered.
-
enumerator NOT_TERMINATED
Backend is still running.
-
enumerator SHUTDOWN_REQUESTED
Shutdown requested for non-failure reason (e.g. by SIGINT).
-
enumerator MAXIMUM_NUMBER_OF_ACTIONS_REACHED
Maximum number of actions was reached.
-
enumerator DRIVER_ERROR
Some error in the driver.
-
enumerator FIRST_ACTION_TIMEOUT
First action timeout was triggered.
-
enumerator NEXT_ACTION_TIMEOUT
Next action timeout was triggered.
-
enumerator NOT_TERMINATED
Functions
-
template<typename Types>
void create_blmc_can_robot_python_bindings(pybind11::module &m)¶ Create Python bindings for the specified BLMC-CAN-robot Types.
With this function, Python bindings can easily be created for new robots that are based on the NJointRobotTypes. Example:
PYBIND11_MODULE(py_fortytwo_types, m) { create_blmc_can_python_bindings<NJointRobotTypes<42>>(m); }
- Template Parameters:
Types – An instance of NJointRobotTypes.
- Parameters:
m – The second argument of the PYBIND11_MODULE macro.
-
template<typename Action, typename Observation>
void create_robot_data_python_bindings(pybind11::module &m)¶ Create Python bindings for the RobotData classes.
-
template<typename Action, typename Observation>
void create_robot_backend_python_bindings(pybind11::module &m)¶ Create Python bindings for RobotBackend.
-
template<typename Action, typename Observation>
void create_robot_frontend_python_bindings(pybind11::module &m)¶ Create Python bindings for RobotFrontend.
-
template<typename Action, typename Observation>
void create_robot_logger_python_bindings(pybind11::module &m)¶ Create Python bindings for RobotLogger and related classes.
-
template<typename Action, typename Observation>
void create_interface_python_bindings(pybind11::module &m)¶ Create Python bindings for the robot interface classes.
Creates bindings for RobotData, RobotBackend, RobotFrontend and logging-related classes.
Usage Example:
PYBIND11_MODULE(my_robot, m) { create_interface_python_bindings<MyAction, MyObservation>(m); // You still need provide bindings for MyAction and MyObservation! }
- Template Parameters:
Action – The action type that is used for the robot.
Observation – The observation type that is used for the robot.
- Parameters:
m – The second argument of the PYBIND11_MODULE macro.
-
template<size_t N_FINGERS>
struct FingerTypes : public robot_interfaces::RobotInterfaceTypes<NJointAction<N_FINGERS * JOINTS_PER_FINGER>, NFingerObservation<N_FINGERS>>, public robot_interfaces::RobotInterfaceTypes<NJointAction<N_FINGERS * JOINTS_PER_FINGER>, NFingerObservation<N_FINGERS>>¶ - #include <finger_types.hpp>
Types for the Finger robot (basic 3-joint robot).
-
class Loggable
- #include <loggable.hpp>
Subclassed by robot_interfaces::NFingerObservation< N_FINGERS >, robot_interfaces::NFingerObservation< N_FINGERS >, robot_interfaces::NJointAction< N >, robot_interfaces::NJointAction< N >, robot_interfaces::NJointObservation< N >, robot_interfaces::NJointObservation< N >, robot_interfaces::Status, robot_interfaces::Status, robot_interfaces::example::Action, robot_interfaces::example::Action, robot_interfaces::example::Observation, robot_interfaces::example::Observation
Public Functions
-
inline virtual ~Loggable()
-
virtual std::vector<std::string> get_name() = 0
-
virtual std::vector<std::vector<double>> get_data() = 0
-
inline virtual ~Loggable()
-
virtual std::vector<std::string> get_name() = 0
-
virtual std::vector<std::vector<double>> get_data() = 0
-
inline virtual ~Loggable()
-
template<typename Driver>
class MonitoredRobotDriver : public robot_interfaces::RobotDriver<Driver::Action, Driver::Observation>, public robot_interfaces::RobotDriver<Driver::Action, Driver::Observation> - #include <monitored_robot_driver.hpp>
Wrapper for RobotDriver that monitors timing.
Takes a RobotDriver instance as input and forwards all method calls to it. A background loop monitors timing of actions to ensure the following constraints:
The execution of an action does not take longer than
max_action_duration_s_
seconds.The time interval between termination of the previous action and receival of the next one (through
apply_action()
) does not exceedmax_inter_action_duration_s_
.
If these timing constraints are not satisfied, the robot will be shutdown, and no more actions from the outside will be accepted.
This wrapper also makes sure that the
shutdown()
method of the given RobotDriver is called when wrapper is destroyed, so the robot should always be left in a safe state.- Template Parameters:
Action –
Observation –
Public Types
-
typedef std::shared_ptr<Driver> RobotDriverPtr
-
typedef std::shared_ptr<Driver> RobotDriverPtr
Public Functions
-
inline MonitoredRobotDriver(RobotDriverPtr robot_driver, const double max_action_duration_s, const double max_inter_action_duration_s)
Starts a thread for monitoring timing of action execution.
- Parameters:
robot_driver – The actual robot driver instance.
max_action_duration_s – Maximum time allowed for an action to be executed.
max_inter_action_duration_s – Maximum time allowed between end of the previous action and receival of the next one.
-
inline ~MonitoredRobotDriver()
Shuts down the robot and stops the monitoring thread.
-
inline Driver::Action apply_action(const typename Driver::Action &desired_action) final override
Apply desired action on the robot.
If the robot is shut down, no more actions will be applied (the method will just ignore them silently.
- Parameters:
desired_action – The desired action.
- Returns:
The action that is actually applied on the robot (may differ from desired action due to safety limitations).
-
inline virtual void initialize() override
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
inline virtual Driver::Action get_idle_action() override
Return action that is safe to apply while the robot is idle.
Typically this can be an action applying zero torque to all joints but it might be more involved depending on the robot (it could, for example, also be an action to hold the joints in place).
The default implementation simply uses the default constructor of Action, assuming that this is safe to use.
-
inline virtual Driver::Observation get_latest_observation() override
Return the latest observation immediately.
- Returns:
Observation
-
inline virtual std::optional<std::string> get_error() override
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
inline virtual void shutdown() final override
Shut down the robot safely.
After shutdown, actions sent by the user are ignored.
-
inline MonitoredRobotDriver(RobotDriverPtr robot_driver, const double max_action_duration_s, const double max_inter_action_duration_s)
Starts a thread for monitoring timing of action execution.
- Parameters:
robot_driver – The actual robot driver instance.
max_action_duration_s – Maximum time allowed for an action to be executed.
max_inter_action_duration_s – Maximum time allowed between end of the previous action and receival of the next one.
-
inline ~MonitoredRobotDriver()
Shuts down the robot and stops the monitoring thread.
-
inline Driver::Action apply_action(const typename Driver::Action &desired_action) final override
Apply desired action on the robot.
If the robot is shut down, no more actions will be applied (the method will just ignore them silently.
- Parameters:
desired_action – The desired action.
- Returns:
The action that is actually applied on the robot (may differ from desired action due to safety limitations).
-
inline virtual void initialize() override
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
inline virtual Driver::Action get_idle_action() override
Return action that is safe to apply while the robot is idle.
Typically this can be an action applying zero torque to all joints but it might be more involved depending on the robot (it could, for example, also be an action to hold the joints in place).
The default implementation simply uses the default constructor of Action, assuming that this is safe to use.
-
inline virtual Driver::Observation get_latest_observation() override
Return the latest observation immediately.
- Returns:
Observation
-
inline virtual std::optional<std::string> get_error() override
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
inline virtual void shutdown() final override
Shut down the robot safely.
After shutdown, actions sent by the user are ignored.
-
template<size_t N_FINGERS>
struct NFingerObservation : public robot_interfaces::Loggable, public robot_interfaces::Loggable¶ - #include <n_finger_observation.hpp>
Observation of a Finger robot.
Values like angular position, velocity or torque of the joints are represented as a 1-dimensional vector with one element per joint. The order of the joints in these vectors is as follows:
0. Finger 1, upper joint 1. Finger 1, middle joint 2. Finger 1, lower joint 3. Finger 2, upper joint 4. Finger 2, middle joint 5. Finger 2, lower joint ... #. Finger n, upper joint #. Finger n, middle joint #. Finger n, lower joint
- Template Parameters:
N_FINGERS – Number of fingers.
Public Types
-
typedef Eigen::Matrix<double, num_joints, 1> JointVector¶
-
typedef Eigen::Matrix<double, num_fingers, 1> FingerVector¶
-
typedef Eigen::Matrix<double, num_joints, 1> JointVector
-
typedef Eigen::Matrix<double, num_fingers, 1> FingerVector
Public Functions
-
inline virtual std::vector<std::string> get_name() override¶
-
inline virtual std::vector<std::vector<double>> get_data() override¶
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name() override
-
inline virtual std::vector<std::vector<double>> get_data() override
Public Members
-
JointVector position = JointVector::Zero()¶
Measured angular position of all joints in radian.
-
JointVector velocity = JointVector::Zero()¶
Measured velocity of all joints in radian/second.
-
JointVector torque = JointVector::Zero()¶
Measured torques of all joints in Nm.
-
FingerVector tip_force = FingerVector::Zero()¶
Measurements of the pressure sensors at the finger tips.
One per finger. Ranges between 0 and 1 without specific unit. Note that not all fingers are equipped with an actual sensor! For fingers without sensor, this value is undefined.
-
template<size_t N>
struct NJointAction : public robot_interfaces::Loggable, public robot_interfaces::Loggable¶ - #include <n_joint_action.hpp>
Action of a generic n-joint robot.
This action type can be used for all n-joint robots that expect torque or position commands on joint-level.
- Template Parameters:
N – Number of joints.
Public Functions
-
inline virtual std::vector<std::string> get_name() override¶
-
inline virtual std::vector<std::vector<double>> get_data() override¶
-
inline NJointAction(Vector torque = Vector::Zero(), Vector position = None(), Vector position_kp = None(), Vector position_kd = None())¶
Create action with desired torque and (optional) position.
The resulting torque command sent to the robot is
To disable the position controller, set the target position to NaN. The controller is executed joint-wise, so it is possible to run it only for some joints by setting a target position for these joints and setting the others to NaN.sent_torque = torque + PD(position)
The specified torque is always added to the result of the position controller, so if you only want to run the position controller, make sure to set
torque
to zero for all joints.For more explicit code, the static factory methods
Torque
,Position
,TorqueAndPosition
andZero
should be used instead directly creating actions through this constructor.- Parameters:
torque – Desired torque.
position – Desired position. Set values to NaN to disable position controller for the corresponding joints
position_kp – P-gains for the position controller. Set to NaN to use default values.
position_kd – D-gains for the position controller. Set to NaN to use default values.
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name() override
-
inline virtual std::vector<std::vector<double>> get_data() override
-
inline NJointAction(Vector torque = Vector::Zero(), Vector position = None(), Vector position_kp = None(), Vector position_kd = None())
Create action with desired torque and (optional) position.
The resulting torque command sent to the robot is
To disable the position controller, set the target position to NaN. The controller is executed joint-wise, so it is possible to run it only for some joints by setting a target position for these joints and setting the others to NaN.sent_torque = torque + PD(position)
The specified torque is always added to the result of the position controller, so if you only want to run the position controller, make sure to set
torque
to zero for all joints.For more explicit code, the static factory methods
Torque
,Position
,TorqueAndPosition
andZero
should be used instead directly creating actions through this constructor.- Parameters:
torque – Desired torque.
position – Desired position. Set values to NaN to disable position controller for the corresponding joints
position_kp – P-gains for the position controller. Set to NaN to use default values.
position_kd – D-gains for the position controller. Set to NaN to use default values.
Public Members
Public Static Functions
-
static inline NJointAction Torque(Vector torque)¶
Create an action that only contains a torque command.
- Parameters:
torque – Desired torque.
- Returns:
Pure “torque action”.
-
static inline NJointAction Position(Vector position, Vector kp = None(), Vector kd = None())¶
Create an action that only contains a position command.
- Parameters:
position – Desired position.
kp – P-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
kd – D-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
- Returns:
Pure “position action”.
-
static inline NJointAction TorqueAndPosition(Vector torque, Vector position, Vector position_kp = None(), Vector position_kd = None())¶
Create an action with both torque and position commands.
- Parameters:
torque – Desired torque.
position – Desired position. Set to NaN for specific joints to disable position control for this joint.
kp – P-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
kd – D-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
- Returns:
Action with both torque and position commands.
-
static inline NJointAction Zero()¶
Create a zero-torque action.
- Returns:
Zero-torque action with position control disabled.
-
static inline Vector None()¶
Create a NaN-Vector.
Helper function to set defaults for position.
- Returns:
Vector with all elements set to NaN.
-
static inline NJointAction Torque(Vector torque)
Create an action that only contains a torque command.
- Parameters:
torque – Desired torque.
- Returns:
Pure “torque action”.
-
static inline NJointAction Position(Vector position, Vector kp = None(), Vector kd = None())
Create an action that only contains a position command.
- Parameters:
position – Desired position.
kp – P-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
kd – D-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
- Returns:
Pure “position action”.
-
static inline NJointAction TorqueAndPosition(Vector torque, Vector position, Vector position_kp = None(), Vector position_kd = None())
Create an action with both torque and position commands.
- Parameters:
torque – Desired torque.
position – Desired position. Set to NaN for specific joints to disable position control for this joint.
kp – P-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
kd – D-gain for position controller. If not set, default is used. Set to NaN for specific joints to use default for this joint.
- Returns:
Action with both torque and position commands.
-
static inline NJointAction Zero()
Create a zero-torque action.
- Returns:
Zero-torque action with position control disabled.
-
static inline Vector None()
Create a NaN-Vector.
Helper function to set defaults for position.
- Returns:
Vector with all elements set to NaN.
-
template<size_t N>
struct NJointObservation : public robot_interfaces::Loggable, public robot_interfaces::Loggable¶ - #include <n_joint_observation.hpp>
Basic observation for a generic n-joint robot.
Simple observation type with position, velocity and torque for each joint.
- Template Parameters:
N – Number of joints.
Public Functions
-
inline virtual std::vector<std::string> get_name() override¶
-
inline virtual std::vector<std::vector<double>> get_data() override¶
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name() override
-
inline virtual std::vector<std::vector<double>> get_data() override
Public Members
-
template<size_t N>
struct SimpleNJointRobotTypes : public robot_interfaces::RobotInterfaceTypes<NJointAction<N>, NJointObservation<N>>, public robot_interfaces::RobotInterfaceTypes<NJointAction<N>, NJointObservation<N>>¶ - #include <n_joint_robot_types.hpp>
Collection of types for a generic N-joint BLMC robot.
Defines all the types needed to set up an interface to a generic N-joint BLMC robot that expects as Action a simple vector of N torque commands and provides N observations containing measured joint angle, velocity and torque.
- Template Parameters:
N – Number of joints
-
template<typename Types, typename = int>
struct BindTipForceIfExists¶ - #include <pybind_finger.hpp>
@bind Add Python bindings for Types::Observaton::tip_force if it exists.
Uses black SFINAE magic to add bindings for “tip_force” if it exists. Further the pickle functions differ due to this, so handle this here as well.
Usage:
This is based on https://stackoverflow.com/a/16000226, see there for an explanation how/why this works.BindTipForceIfExists<Types>::bind(pybind_class);
- template<typename Types> tip_force, 0)>
- #include <pybind_finger.hpp>
Public Static Functions
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)¶
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)¶
-
template<typename Action, typename Observation, typename Driver, typename Data = SingleProcessRobotData<Action, Observation>>
class Robot : public robot_interfaces::RobotFrontend<Action, Observation>, public robot_interfaces::RobotFrontend<Action, Observation> - #include <robot.hpp>
RobotFrontend that construct and encapsulates its related RobotBackend.
It also construct and starts the robot driver.
Public Functions
-
template<typename ...Args>
inline Robot(double max_action_duration_s, double max_inter_action_duration_s, Args... args) - Parameters:
max_action_duration_s – See MonitoredRobotDriver.
max_inter_action_duration_s – See MonitoredRobotDriver.
args – Arguments for instantiating Driver
-
template<typename ...Args>
inline Robot(Args... args) Robot which instantiates a non real time mode backend.
- Parameters:
max_action_duration_s – See MonitoredRobotDriver.
max_inter_action_duration_s – See MonitoredRobotDriver.
args – Arguments for instantiating Driver
-
inline void initialize()
initialize the backend
-
inline const Data &get_data() const
return the data shared by the frontend and the backend.
-
template<typename ...Args>
inline Robot(double max_action_duration_s, double max_inter_action_duration_s, Args... args) - Parameters:
max_action_duration_s – See MonitoredRobotDriver.
max_inter_action_duration_s – See MonitoredRobotDriver.
args – Arguments for instantiating Driver
-
template<typename ...Args>
inline Robot(Args... args) Robot which instantiates a non real time mode backend.
- Parameters:
max_action_duration_s – See MonitoredRobotDriver.
max_inter_action_duration_s – See MonitoredRobotDriver.
args – Arguments for instantiating Driver
-
inline void initialize()
initialize the backend
-
inline const Data &get_data() const
return the data shared by the frontend and the backend.
-
template<typename ...Args>
-
template<typename Action, typename Observation>
class RobotBackend - #include <robot_backend.hpp>
Communication link between RobotDriver and RobotData.
At each time-step, it gets the observation from the RobotDriver and writes it to RobotData, and it takes the desired_action from RobotData and applies it on the RobotDriver.
- Template Parameters:
Action –
Observation –
Public Types
-
typedef std::shared_ptr<RobotBackend<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotBackend<Action, Observation>> ConstPtr
-
typedef std::shared_ptr<RobotBackend<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotBackend<Action, Observation>> ConstPtr
Public Functions
- Parameters:
robot_driver – Driver instance for the actual robot.
robot_data – Data is send to/retrieved from here.
real_time_mode – Enable/disable real-time mode. In real-time mode, the backend will repeat previous actions if the new one is not provided in time or fail with an error if the allowed number of repetitions is exceeded. In non-real-time mode, it will simply block and wait until the action is provided.
first_action_timeout – See RobotBackend::first_action_timeout_.
max_number_of_actions – See RobotBackend::max_number_of_actions_.
-
inline virtual ~RobotBackend()
-
inline uint32_t get_max_action_repetitions()
-
inline void set_max_action_repetitions(const uint32_t &max_action_repetitions)
Set how often an action is repeated if no new one is provided.
If the next action is due to be executed but the user did not provide one yet (i.e. there is no new action in the robot data time series), the last action will be repeated by automatically adding it to the time series again.
Use this this method to specify how often the action shall be repeated (default is 0, i.e. no repetition at all). If this limit is exceeded, the robot will be shut down and the RobotBackend stops.
Note: This is ignored in non-real-time mode.
- Parameters:
max_action_repetitions –
-
inline void initialize()
-
inline void request_shutdown()
Request shutdown of the backend loop.
The loop may take some time to actually terminate after calling this function. Use wait_until_terminated() to ensure it has really terminated.
-
inline void wait_until_first_action() const
Wait until the first desired action is received.
-
inline int wait_until_terminated() const
Wait until the backend loop terminates.
- Returns:
Termination code (see RobotBackendTerminationReason).
-
inline bool is_running() const
Check if the backend loop is still running.
- Returns:
True if the loop is still running.
-
inline int get_termination_reason() const
Get the termination reason.
-
inline RobotBackend(std::shared_ptr<RobotDriver<Action, Observation>> robot_driver, std::shared_ptr<RobotData<Action, Observation>> robot_data, const bool real_time_mode = true, const double first_action_timeout = std::numeric_limits<double>::infinity(), const uint32_t max_number_of_actions = 0)
- Parameters:
robot_driver – Driver instance for the actual robot.
robot_data – Data is send to/retrieved from here.
real_time_mode – Enable/disable real-time mode. In real-time mode, the backend will repeat previous actions if the new one is not provided in time or fail with an error if the allowed number of repetitions is exceeded. In non-real-time mode, it will simply block and wait until the action is provided.
first_action_timeout – See RobotBackend::first_action_timeout_.
max_number_of_actions – See RobotBackend::max_number_of_actions_.
-
inline virtual ~RobotBackend()
-
inline uint32_t get_max_action_repetitions()
-
inline void set_max_action_repetitions(const uint32_t &max_action_repetitions)
Set how often an action is repeated if no new one is provided.
If the next action is due to be executed but the user did not provide one yet (i.e. there is no new action in the robot data time series), the last action will be repeated by automatically adding it to the time series again.
Use this this method to specify how often the action shall be repeated (default is 0, i.e. no repetition at all). If this limit is exceeded, the robot will be shut down and the RobotBackend stops.
Note: This is ignored in non-real-time mode.
- Parameters:
max_action_repetitions –
-
inline void initialize()
-
inline void request_shutdown()
Request shutdown of the backend loop.
The loop may take some time to actually terminate after calling this function. Use wait_until_terminated() to ensure it has really terminated.
-
inline void wait_until_first_action() const
Wait until the first desired action is received.
-
inline int wait_until_terminated() const
Wait until the backend loop terminates.
- Returns:
Termination code (see RobotBackendTerminationReason).
-
inline bool is_running() const
Check if the backend loop is still running.
- Returns:
True if the loop is still running.
-
inline int get_termination_reason() const
Get the termination reason.
-
template<typename Action, typename Observation>
class RobotData - #include <robot_data.hpp>
Contains all the input and output data of the robot.
This means the
desired_action
which was requested by the robot userapplied_action
which was actually applied and may not be and may not be identical to desired_action for safety reasonsobservation
made by the robotstatus
which keeps track of timing issues and errors.
See this graph to understand how they relate to each other precisely in terms of time:
|------ t = 0 ------|------ t = 1 ------| |----- action0 -----|----- action1 -----| o o o b b b s s s 0 1 2
- Template Parameters:
Action – Type of the actions.
Observation – Type of the observations.
Subclassed by robot_interfaces::MultiProcessRobotData< Action, Observation >, robot_interfaces::MultiProcessRobotData< Action, Observation >, robot_interfaces::SingleProcessRobotData< Action, Observation >, robot_interfaces::SingleProcessRobotData< Action, Observation >
Public Types
-
typedef std::shared_ptr<RobotData<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotData<Action, Observation>> ConstPtr
-
typedef std::shared_ptr<RobotData<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotData<Action, Observation>> ConstPtr
Public Members
-
std::shared_ptr<time_series::TimeSeriesInterface<Action>> desired_action
Time series of the desired actions.
-
std::shared_ptr<time_series::TimeSeriesInterface<Action>> applied_action
Time series of the actually applied actions (due to safety.
-
std::shared_ptr<time_series::TimeSeriesInterface<Observation>> observation
Time series of the observations retrieved from the robot.
-
std::shared_ptr<time_series::TimeSeriesInterface<Status>> status
Time series of status messages.
-
template<typename Action, typename Observation>
class SingleProcessRobotData : public robot_interfaces::RobotData<Action, Observation>, public robot_interfaces::RobotData<Action, Observation> - #include <robot_data.hpp>
RobotData instance using single process time series.
Use this class if all modules accessing the data are running in the same process. If modules run in separate processes, use MultiProcessRobotData instead.
See also
Public Functions
-
inline SingleProcessRobotData(size_t history_length = 1000)
Construct the time series for the robot data.
- Parameters:
history_length – History length of the time series.
-
inline SingleProcessRobotData(size_t history_length = 1000)
Construct the time series for the robot data.
- Parameters:
history_length – History length of the time series.
-
inline SingleProcessRobotData(size_t history_length = 1000)
-
template<typename Action, typename Observation>
class MultiProcessRobotData : public robot_interfaces::RobotData<Action, Observation>, public robot_interfaces::RobotData<Action, Observation> - #include <robot_data.hpp>
RobotData instance using multi process time series.
Use this class if modules accessing the data are running in separate processes. When all modules run as threads in the same process, this class can be used as well, however, SingleProcessRobotData might be more efficient in that case.
See also
Public Functions
-
inline MultiProcessRobotData(const std::string &shared_memory_id_prefix, bool is_master, size_t history_length = 1000)
Construct the time series for the robot data.
- Todo:
Make this constructor protected and implement factory methods like in MultiprocessTimeSeries..
- Parameters:
shared_memory_id_prefix – Prefix for the shared memory IDs. Since each time series needs its own memory ID, the given value is used as prefix and unique suffixes are appended. Make sure to use a prefix that cannot lead to name collisions on your system.
is_master – If set to true, this instance will clear the shared memory on construction and destruction. Only one instance should act as master in a multi-process setup.
history_length – History length of the time series. Ignored if
is_master == false
.
-
inline MultiProcessRobotData(const std::string &shared_memory_id_prefix, bool is_master, size_t history_length = 1000)
Construct the time series for the robot data.
- Todo:
Make this constructor protected and implement factory methods like in MultiprocessTimeSeries..
- Parameters:
shared_memory_id_prefix – Prefix for the shared memory IDs. Since each time series needs its own memory ID, the given value is used as prefix and unique suffixes are appended. Make sure to use a prefix that cannot lead to name collisions on your system.
is_master – If set to true, this instance will clear the shared memory on construction and destruction. Only one instance should act as master in a multi-process setup.
history_length – History length of the time series. Ignored if
is_master == false
.
-
inline MultiProcessRobotData(const std::string &shared_memory_id_prefix, bool is_master, size_t history_length = 1000)
-
template<typename TAction, typename TObservation>
class RobotDriver - #include <robot_driver.hpp>
Driver for interfacing the actual robot hardware or simulation.
Interface to the robot used by the subsequent classes. Any robot (be it real or simulation) has to derive from this class and implement the functions apply_action(), get_latest_observation() and shutdown(). This Base class provides some timing logic around those three functions. It makes sure that after the first call of apply_action(), it is always called again after some specified time, otherwise the shutdown() method will be called. This Base class also makes sure that the apply_action() function itself does not take more time than expected.
- Template Parameters:
Action –
Observation –
Public Types
-
typedef TAction Action
-
typedef TObservation Observation
-
typedef TAction Action
-
typedef TObservation Observation
Public Functions
-
inline virtual ~RobotDriver()
-
virtual void initialize() = 0
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
virtual Action apply_action(const Action &desired_action) = 0
Apply action immediately and block until it is executed.
This method must apply the desired_action immediately when it is called, and only return once the action has been executed completely. This way we can accommodate both simulators and real robots with this interface.
- Parameters:
desired_action – The action we want to apply.
- Returns:
The action that was actually applied (since due to safety reasons it might not be possible to apply the desired action).
-
virtual Observation get_latest_observation() = 0
Return the latest observation immediately.
- Returns:
Observation
-
virtual std::optional<std::string> get_error() = 0
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
virtual void shutdown() = 0
Shut down the robot safely.
Use this method if your robot needs to perform some action when shutting down, e.g. to move it to a defined rest position.
-
inline virtual Action get_idle_action()
Return action that is safe to apply while the robot is idle.
Typically this can be an action applying zero torque to all joints but it might be more involved depending on the robot (it could, for example, also be an action to hold the joints in place).
The default implementation simply uses the default constructor of Action, assuming that this is safe to use.
-
inline virtual ~RobotDriver()
-
virtual void initialize() = 0
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
virtual Action apply_action(const Action &desired_action) = 0
Apply action immediately and block until it is executed.
This method must apply the desired_action immediately when it is called, and only return once the action has been executed completely. This way we can accommodate both simulators and real robots with this interface.
- Parameters:
desired_action – The action we want to apply.
- Returns:
The action that was actually applied (since due to safety reasons it might not be possible to apply the desired action).
-
virtual Observation get_latest_observation() = 0
Return the latest observation immediately.
- Returns:
Observation
-
virtual std::optional<std::string> get_error() = 0
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
virtual void shutdown() = 0
Shut down the robot safely.
Use this method if your robot needs to perform some action when shutting down, e.g. to move it to a defined rest position.
-
inline virtual Action get_idle_action()
Return action that is safe to apply while the robot is idle.
Typically this can be an action applying zero torque to all joints but it might be more involved depending on the robot (it could, for example, also be an action to hold the joints in place).
The default implementation simply uses the default constructor of Action, assuming that this is safe to use.
-
template<typename Action, typename Observation>
class RobotFrontend - #include <robot_frontend.hpp>
Communication link between RobotData and the user.
Takes care of communication between the RobotData and the user. It is just a thin wrapper around RobotData to facilitate interaction and also to make sure the user cannot use RobotData in incorrect ways.
- Template Parameters:
Action –
Observation –
Subclassed by robot_interfaces::Robot< Action, Observation, Driver, Data >, robot_interfaces::Robot< Action, Observation, Driver, Data >
Public Types
-
typedef std::shared_ptr<RobotFrontend<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotFrontend<Action, Observation>> ConstPtr
-
typedef time_series::Timestamp TimeStamp
-
typedef std::shared_ptr<RobotFrontend<Action, Observation>> Ptr
-
typedef std::shared_ptr<const RobotFrontend<Action, Observation>> ConstPtr
-
typedef time_series::Timestamp TimeStamp
Public Functions
-
inline Observation get_observation(const TimeIndex &t) const
Get observation of time step t.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The observation of time step t.
-
inline Action get_desired_action(const TimeIndex &t) const
Get the desired action of time step t.
The desired action is the action as it is passed by the user in append_desired_action.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The desired action of time step t.
-
inline Action get_applied_action(const TimeIndex &t) const
Get the applied action of time step t.
The applied action is the one that was actually applied to the robot based on the desired action of that time step. It may differ from the desired one e.g. due to some safety checks which limit the maximum torque. If and how the action is modified depends on the implementation of the RobotDriver.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The applied action of time step t.
-
inline TimeStamp get_timestamp_ms(const TimeIndex &t) const
Get the timestamp of time step t.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
Timestamp of time step t.
-
inline TimeIndex get_current_timeindex() const
Get the current time index.
- Returns:
The latest time index for which observations are available.
-
inline TimeIndex append_desired_action(const Action &desired_action)
Append a desired action to the action time series.
This will append an action to the “desired actions” time series. Note that this does not block until the action is actually executed. The time series acts like a queue from which the RobotBackend takes the actions one by one to send them to the actual robot. It is possible to call this method multiple times in a row to already provide actions for the next time steps.
The time step at which the given action will be applied is returned by this method.
- Parameters:
desired_action – The action that shall be applied on the robot. Note that the actually applied action might be different depending on the implementation of the RobotDriver (see get_applied_action).
- Returns:
Time step at which the action will be applied.
-
inline void wait_until_timeindex(const TimeIndex &t) const
Wait until the specified time step is reached.
- Parameters:
t – Time step until which is waited.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
-
inline RobotFrontend(std::shared_ptr<RobotData<Action, Observation>> robot_data)
-
inline Observation get_observation(const TimeIndex &t) const
Get observation of time step t.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The observation of time step t.
-
inline Action get_desired_action(const TimeIndex &t) const
Get the desired action of time step t.
The desired action is the action as it is passed by the user in append_desired_action.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The desired action of time step t.
-
inline Action get_applied_action(const TimeIndex &t) const
Get the applied action of time step t.
The applied action is the one that was actually applied to the robot based on the desired action of that time step. It may differ from the desired one e.g. due to some safety checks which limit the maximum torque. If and how the action is modified depends on the implementation of the RobotDriver.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
The applied action of time step t.
-
inline TimeStamp get_timestamp_ms(const TimeIndex &t) const
Get the timestamp of time step t.
- Parameters:
t – Index of the time step. If t is in the future, this method will block and wait.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
- Returns:
Timestamp of time step t.
-
inline TimeIndex get_current_timeindex() const
Get the current time index.
- Returns:
The latest time index for which observations are available.
-
inline TimeIndex append_desired_action(const Action &desired_action)
Append a desired action to the action time series.
This will append an action to the “desired actions” time series. Note that this does not block until the action is actually executed. The time series acts like a queue from which the RobotBackend takes the actions one by one to send them to the actual robot. It is possible to call this method multiple times in a row to already provide actions for the next time steps.
The time step at which the given action will be applied is returned by this method.
- Parameters:
desired_action – The action that shall be applied on the robot. Note that the actually applied action might be different depending on the implementation of the RobotDriver (see get_applied_action).
- Returns:
Time step at which the action will be applied.
-
inline void wait_until_timeindex(const TimeIndex &t) const
Wait until the specified time step is reached.
- Parameters:
t – Time step until which is waited.
- Throws:
std::invalid_argument – if t is too old and not in the time series buffer anymore.
-
template<typename Action, typename Observation, typename Status_t = Status>
struct RobotLogEntry¶ - #include <robot_log_entry.hpp>
Robot log entry used for binary log format.
Contains all the robot data of one time step.
Public Functions
-
template<class Archive>
inline void serialize(Archive &archive)
-
template<class Archive>
-
template<typename Action, typename Observation, typename Status_t = Status>
class RobotBinaryLogReader - #include <robot_log_reader.hpp>
Read the data from a robot log file.
The data is read from the specified file and stored to the
data
member where it can be accessed.Public Types
-
typedef RobotLogEntry<Action, Observation, Status_t> LogEntry
-
typedef RobotLogEntry<Action, Observation, Status_t> LogEntry
Public Functions
-
inline RobotBinaryLogReader()
-
inline RobotBinaryLogReader(const std::string &filename)
Read data from the specified file.
The data is stored to RobotBinaryLogReader::data.
- Parameters:
filename – Path to the robot log file.
-
inline void read_file(const std::string &filename)
Read data from the specified file.
The data is stored to RobotBinaryLogReader::data.
- Parameters:
filename – Path to the robot log file.
-
inline void write_file(const std::string &filename)
Write data to the specified file.
- Parameters:
filename – Path to the output file.
-
inline RobotBinaryLogReader()
-
inline RobotBinaryLogReader(const std::string &filename)
Read data from the specified file.
The data is stored to RobotBinaryLogReader::data.
- Parameters:
filename – Path to the robot log file.
-
inline void read_file(const std::string &filename)
Read data from the specified file.
The data is stored to RobotBinaryLogReader::data.
- Parameters:
filename – Path to the robot log file.
-
inline void write_file(const std::string &filename)
Write data to the specified file.
- Parameters:
filename – Path to the output file.
Public Members
-
std::vector<LogEntry> data
Public Static Attributes
-
static constexpr uint32_t FORMAT_VERSION = 2
-
typedef RobotLogEntry<Action, Observation, Status_t> LogEntry
-
template<typename Action, typename Observation>
class RobotLogger - #include <robot_logger.hpp>
Log robot data (observations, actions, status) to file.
Logs for each time step the time index, timestamp, and the values Observation, Action, and Status. The data is written to a text file, one line per time step with values separated by spaces. This format can easily be read e.g. with NumPy or Pandas.
There are different ways of using the logger:
Using start() and stop_and_save(): The logger runs a thread in which it copies all data to an internal buffer while the robot is running. When calling stop_and_save() the content of the buffer is stored to a file (either binary or text). This is the recommended method for most applications.
Using save_current_robot_data() or save_current_robot_data_binary(): Call this to log data that is currently held in the robot data time series. For this method, the logger doesn’t use an own buffer, so no data is copied while the robot is running. However, the possible time span for logging is limited by the size of the robot data time series.
- Template Parameters:
Public Types
-
enum class Format
Enumeration of possible log file formats.
Values:
-
enumerator BINARY
-
enumerator CSV
-
enumerator CSV_GZIP
-
enumerator BINARY
-
enumerator CSV
-
enumerator CSV_GZIP
-
enumerator BINARY
-
enum class Format
Enumeration of possible log file formats.
Values:
-
enumerator BINARY
-
enumerator CSV
-
enumerator CSV_GZIP
-
enumerator BINARY
-
enumerator CSV
-
enumerator CSV_GZIP
-
enumerator BINARY
-
typedef RobotLogEntry<Action, Observation> LogEntry
-
typedef RobotLogEntry<Action, Observation> LogEntry
Public Functions
Initialize logger.
- Parameters:
robot_data – Pointer to the robot data instance.
buffer_limit – Max. size of the log buffer (in timesteps). If the buffer is full, old time steps will be dropped as new ones are added.
-
RobotLogger(RobotLogger&&) = default
-
inline virtual ~RobotLogger()
-
inline void start()
Start logging using an internal buffer.
The buffer is limited by the
buffer_limit
argument of the constructor. If the limit is reached, the logger stops automatically.If the logger is already running, this is a noop.
-
inline void stop()
Stop logging.
If the logger is already stopped, this is a noop.
-
inline void reset()
Clear the log buffer.
-
inline void stop_and_save(const std::string &filename, Format log_format)
Stop logging and save logged messages to a file.
- Parameters:
filename – Path to the output file. Existing files will be overwritten.
-
inline void save_current_robot_data(const std::string &filename, long int start_index = 0, long int end_index = -1)
Write current content of robot data to CSV log file.
Write data of the time steps
[start_index, end_index)
to a log file. This assumes that the specified range is completely included in the active robot data buffer. If this is not the case, only the time steps which are still held in the buffer will be logged.With the default values for start_index and end_index, the whole content of the current buffer is logged.
- Parameters:
filename – Path to the log file. Existing files will be overwritten!
start_index – Time index at which to start logging. If not specified, the whole buffer is logged.
end_index – Time index at which to stop logging. This is exclusive, i.e. the specified time index itself will not be part of the log. If set to a negative value (default) or a value greater than the newest time index, the newest time index is used instead (see newest_timeindex()).
- Throws:
std::runtime_error – If called while the logger thread is running. In case the logger thread was started via
start()
, it needs to be stopped by callingstop()
beforesave_current_robot_data()
can be used.
-
inline void save_current_robot_data_binary(const std::string &filename, long int start_index = 0, long int end_index = -1)
Like save_current_robot_data but using binary file format.
-
inline RobotLogger(std::shared_ptr<robot_interfaces::RobotData<Action, Observation>> robot_data, size_t buffer_limit)
Initialize logger.
- Parameters:
robot_data – Pointer to the robot data instance.
buffer_limit – Max. size of the log buffer (in timesteps). If the buffer is full, old time steps will be dropped as new ones are added.
-
RobotLogger(RobotLogger&&) = default
-
inline virtual ~RobotLogger()
-
inline void start()
Start logging using an internal buffer.
The buffer is limited by the
buffer_limit
argument of the constructor. If the limit is reached, the logger stops automatically.If the logger is already running, this is a noop.
-
inline void stop()
Stop logging.
If the logger is already stopped, this is a noop.
-
inline void reset()
Clear the log buffer.
-
inline void stop_and_save(const std::string &filename, Format log_format)
Stop logging and save logged messages to a file.
- Parameters:
filename – Path to the output file. Existing files will be overwritten.
-
inline void save_current_robot_data(const std::string &filename, long int start_index = 0, long int end_index = -1)
Write current content of robot data to CSV log file.
Write data of the time steps
[start_index, end_index)
to a log file. This assumes that the specified range is completely included in the active robot data buffer. If this is not the case, only the time steps which are still held in the buffer will be logged.With the default values for start_index and end_index, the whole content of the current buffer is logged.
- Parameters:
filename – Path to the log file. Existing files will be overwritten!
start_index – Time index at which to start logging. If not specified, the whole buffer is logged.
end_index – Time index at which to stop logging. This is exclusive, i.e. the specified time index itself will not be part of the log. If set to a negative value (default) or a value greater than the newest time index, the newest time index is used instead (see newest_timeindex()).
- Throws:
std::runtime_error – If called while the logger thread is running. In case the logger thread was started via
start()
, it needs to be stopped by callingstop()
beforesave_current_robot_data()
can be used.
-
inline void save_current_robot_data_binary(const std::string &filename, long int start_index = 0, long int end_index = -1)
Like save_current_robot_data but using binary file format.
-
template<typename ObservationType, typename InfoType = None>
class SensorBackend - #include <sensor_backend.hpp>
Communication link between SensorData and SensorDriver.
At each instant, it checks if the sensor can be accessed, and then gets the observation from it (the observation type depends on the sensor) and appends it to the sensor data.
- Template Parameters:
ObservationType –
Public Types
-
typedef std::shared_ptr<SensorBackend<ObservationType, InfoType>> Ptr
-
typedef std::shared_ptr<const SensorBackend<ObservationType, InfoType>> ConstPtr
-
typedef std::shared_ptr<SensorBackend<ObservationType, InfoType>> Ptr
-
typedef std::shared_ptr<const SensorBackend<ObservationType, InfoType>> ConstPtr
Public Functions
- Parameters:
sensor_driver – Driver instance for the sensor.
sensor_data – Data is sent to/retrieved from here.
-
SensorBackend(SensorBackend&&) = default
-
inline void shutdown()
Stop the backend thread.
-
inline virtual ~SensorBackend()
-
inline SensorBackend(std::shared_ptr<SensorDriver<ObservationType, InfoType>> sensor_driver, std::shared_ptr<SensorData<ObservationType, InfoType>> sensor_data)
- Parameters:
sensor_driver – Driver instance for the sensor.
sensor_data – Data is sent to/retrieved from here.
-
SensorBackend(SensorBackend&&) = default
-
inline void shutdown()
Stop the backend thread.
-
inline virtual ~SensorBackend()
-
template<typename Observation, typename Info = None>
class SensorData - #include <sensor_data.hpp>
Contains the data coming from the sensors.
- Template Parameters:
Observation – Type of the sensor observation.
Public Types
-
typedef std::shared_ptr<SensorData<Observation, Info>> Ptr
-
typedef std::shared_ptr<const SensorData<Observation, Info>> ConstPtr
-
typedef std::shared_ptr<SensorData<Observation, Info>> Ptr
-
typedef std::shared_ptr<const SensorData<Observation, Info>> ConstPtr
Public Members
-
std::shared_ptr<time_series::TimeSeriesInterface<Info>> sensor_info
Static information about the sensor.
Note: A time series is used here for convenience to handle the shared memory aspect. However, this is intended to only hold one element that doesn’t change over time.
-
std::shared_ptr<time_series::TimeSeriesInterface<Observation>> observation
Time series of the sensor observations.
-
template<typename Observation, typename Info = None>
class SingleProcessSensorData : public robot_interfaces::SensorData<Observation, None>, public robot_interfaces::SensorData<Observation, None> - #include <sensor_data.hpp>
SensorData instance using single process time series.
Use this class if all modules accessing the data are running in the same process. If modules run in separate processes, use MultiProcessSensorData instead.
See also
Public Functions
-
inline SingleProcessSensorData(size_t history_length = 1000)
-
inline SingleProcessSensorData(size_t history_length = 1000)
-
inline SingleProcessSensorData(size_t history_length = 1000)
-
template<typename Observation, typename Info = None>
class MultiProcessSensorData : public robot_interfaces::SensorData<Observation, None>, public robot_interfaces::SensorData<Observation, None> - #include <sensor_data.hpp>
SensorData instance using multi process time series.
Use this class if modules accessing the data are running in separate processes. When all modules run as threads in the same process, this class can be used as well, however, SingleProcessSensorData might be more efficient in that case.
See also
Public Functions
-
inline MultiProcessSensorData(const std::string &shared_memory_id, bool is_master, size_t history_length = 1000)
-
inline MultiProcessSensorData(const std::string &shared_memory_id, bool is_master, size_t history_length = 1000)
-
inline MultiProcessSensorData(const std::string &shared_memory_id, bool is_master, size_t history_length = 1000)
-
template<typename ObservationType, typename InfoType = None>
class SensorDriver - #include <sensor_driver.hpp>
Base driver class from which all specific sensor drivers should derive.
- Template Parameters:
ObservationType –
Public Functions
-
inline virtual ~SensorDriver()
-
inline virtual InfoType get_sensor_info()
Return static information about the sensor.
This information is expected to be constructed during initialization and to not change later on.
-
virtual ObservationType get_observation() = 0
return the observation
- Returns:
depends on the observation structure of the sensor being interacted with
-
inline virtual ~SensorDriver()
-
inline virtual InfoType get_sensor_info()
Return static information about the sensor.
This information is expected to be constructed during initialization and to not change later on.
-
virtual ObservationType get_observation() = 0
return the observation
- Returns:
depends on the observation structure of the sensor being interacted with
-
template<typename ObservationType, typename InfoType = None>
class SensorFrontend - #include <sensor_frontend.hpp>
Communication link between SensorData and the user.
Exposes the sensor data to the user to enable the user to get observations, timestamps, and timeindices from the timeseries.
- Template Parameters:
ObservationType –
Public Types
-
template<typename Type>
using Timeseries = time_series::TimeSeries<Type>
-
typedef std::shared_ptr<SensorFrontend<ObservationType, InfoType>> Ptr
-
typedef std::shared_ptr<const SensorFrontend<ObservationType, InfoType>> ConstPtr
-
typedef time_series::Timestamp TimeStamp
-
typedef time_series::Index TimeIndex
-
template<typename Type>
using Timeseries = time_series::TimeSeries<Type>
-
typedef std::shared_ptr<SensorFrontend<ObservationType, InfoType>> Ptr
-
typedef std::shared_ptr<const SensorFrontend<ObservationType, InfoType>> ConstPtr
-
typedef time_series::Timestamp TimeStamp
-
typedef time_series::Index TimeIndex
Public Functions
-
inline InfoType get_sensor_info() const
-
inline ObservationType get_observation(const TimeIndex t) const
-
inline ObservationType get_latest_observation() const
-
inline TimeIndex get_current_timeindex() const
-
inline SensorFrontend(std::shared_ptr<SensorData<ObservationType, InfoType>> sensor_data)
-
inline InfoType get_sensor_info() const
-
inline ObservationType get_observation(const TimeIndex t) const
-
inline ObservationType get_latest_observation() const
-
inline TimeIndex get_current_timeindex() const
-
template<typename Observation>
class SensorLogReader - #include <sensor_log_reader.hpp>
Read the data from a sensor log file.
The data is read from the specified file and stored to the
data
member where it can be accessed.- Template Parameters:
Observation – Type of the sensor observation.
Public Types
-
typedef std::tuple<double, Observation> StampedObservation
-
typedef std::tuple<double, Observation> StampedObservation
Public Functions
-
inline SensorLogReader(const std::string &filename)
Read data from the specified file.
The data is stored to SensorLogReader::data.
- Parameters:
filename – Path to the sensor log file.
-
inline void read_file(const std::string &filename)
Read data from the specified file.
The data is stored to SensorLogReader::data.
- Parameters:
filename – Path to the sensor log file.
-
inline SensorLogReader(const std::string &filename)
Read data from the specified file.
The data is stored to SensorLogReader::data.
- Parameters:
filename – Path to the sensor log file.
-
inline void read_file(const std::string &filename)
Read data from the specified file.
The data is stored to SensorLogReader::data.
- Parameters:
filename – Path to the sensor log file.
Public Members
-
std::vector<Observation> data
Observations from the log file.
- Todo:
rename to “observations”
- Todo:
rename to “observations”
-
std::vector<double> timestamps
Timestamps of the time series from which the observations were logged.
-
template<typename Observation, typename InfoType = None>
class SensorLogger - #include <sensor_logger.hpp>
Record sensor observations and store them to a file.
Fetches observations from the given SensorData and buffers them in memory. Buffered observations can be written to a file. For writing to file cereal is used, so the Observation type has to be serializable by cereal.
Usage Example:
auto logger = SensorLogger<int>(sensor_data, BUFFER_LIMIT); logger.start(); // do something logger.stop_and_save("/tmp/sensordata.log");
- Template Parameters:
Observation – Typ of the observation that is recorded.
Public Types
-
typedef std::shared_ptr<SensorData<Observation, InfoType>> DataPtr
-
typedef std::tuple<double, Observation> StampedObservation
-
typedef std::shared_ptr<SensorData<Observation, InfoType>> DataPtr
-
typedef std::tuple<double, Observation> StampedObservation
Public Functions
-
inline SensorLogger(DataPtr sensor_data, size_t buffer_limit)
Initialize the logger.
- Parameters:
sensor_data – Pointer to the SensorData instance from which observations are obtained.
buffer_limit – Maximum number of observations that are logged. When this limit is reached, the logger will stop automatically, that is new observations are not logged anymore.
-
SensorLogger(SensorLogger&&) = default
-
inline ~SensorLogger()
-
inline void start()
Start logging.
If the logger is already running, this is a noop.
-
inline void stop()
Stop logging.
If the logger is already stopped, this is a noop.
-
inline void reset()
Clear the log buffer.
-
inline void stop_and_save(const std::string &filename)
Stop logging and save logged messages to a file.
- Parameters:
filename – Path to the output file. Existing files will be overwritten.
-
inline SensorLogger(DataPtr sensor_data, size_t buffer_limit)
Initialize the logger.
- Parameters:
sensor_data – Pointer to the SensorData instance from which observations are obtained.
buffer_limit – Maximum number of observations that are logged. When this limit is reached, the logger will stop automatically, that is new observations are not logged anymore.
-
SensorLogger(SensorLogger&&) = default
-
inline ~SensorLogger()
-
inline void start()
Start logging.
If the logger is already running, this is a noop.
-
inline void stop()
Stop logging.
If the logger is already stopped, this is a noop.
-
inline void reset()
Clear the log buffer.
-
inline void stop_and_save(const std::string &filename)
Stop logging and save logged messages to a file.
- Parameters:
filename – Path to the output file. Existing files will be overwritten.
-
struct Status : public robot_interfaces::Loggable, public robot_interfaces::Loggable¶
- #include <status.hpp>
Status information from the backend.
Used to report status information that is not directly robot-related from the backend to the frontend.
Public Types
-
enum class ErrorStatus¶
Different types of errors that can occur in the backend.
Values:
-
enumerator NO_ERROR¶
Indicates that there is no error.
-
enumerator DRIVER_ERROR¶
Error reported from the RobotDriver.
An error reported by the low level robot driver (see RobotDriver). This is depending on the driver implementation. It can, for example, be used to report some hardware failure).
-
enumerator BACKEND_ERROR¶
Error from the RobotBackend.
An error which is issued by the back end itself, for example if no new action is provided and the allowed number of repetitions is exceeded.
-
enumerator NO_ERROR
Indicates that there is no error.
-
enumerator DRIVER_ERROR
Error reported from the RobotDriver.
An error reported by the low level robot driver (see RobotDriver). This is depending on the driver implementation. It can, for example, be used to report some hardware failure).
-
enumerator BACKEND_ERROR
Error from the RobotBackend.
An error which is issued by the back end itself, for example if no new action is provided and the allowed number of repetitions is exceeded.
-
enumerator NO_ERROR¶
-
enum class ErrorStatus
Different types of errors that can occur in the backend.
Values:
-
enumerator NO_ERROR
Indicates that there is no error.
-
enumerator DRIVER_ERROR
Error reported from the RobotDriver.
An error reported by the low level robot driver (see RobotDriver). This is depending on the driver implementation. It can, for example, be used to report some hardware failure).
-
enumerator BACKEND_ERROR
Error from the RobotBackend.
An error which is issued by the back end itself, for example if no new action is provided and the allowed number of repetitions is exceeded.
-
enumerator NO_ERROR
Indicates that there is no error.
-
enumerator DRIVER_ERROR
Error reported from the RobotDriver.
An error reported by the low level robot driver (see RobotDriver). This is depending on the driver implementation. It can, for example, be used to report some hardware failure).
-
enumerator BACKEND_ERROR
Error from the RobotBackend.
An error which is issued by the back end itself, for example if no new action is provided and the allowed number of repetitions is exceeded.
-
enumerator NO_ERROR
Public Functions
-
inline void set_error(ErrorStatus error_type, const std::string &message)¶
Set error.
If another error was set before, the old one is kept and the new one ignored.
- Parameters:
error_type – The type of the error.
message – Error message. Will be shortened if it exceeds ERROR_MESSAGE_LENGTH.
-
inline bool has_error() const¶
Check if an error is set.
See error_status and error_message for more details on the error.
Note
If there is an error reported in the status, the robot is not in an operational state anymore. Trying to append another action in the RobotFrontend will result in an exception in this case.
-
inline std::string get_error_message() const¶
Get the error message as std::string.
-
inline virtual std::vector<std::string> get_name() override¶
-
inline virtual std::vector<std::vector<double>> get_data() override¶
-
inline void set_error(ErrorStatus error_type, const std::string &message)
Set error.
If another error was set before, the old one is kept and the new one ignored.
- Parameters:
error_type – The type of the error.
message – Error message. Will be shortened if it exceeds ERROR_MESSAGE_LENGTH.
-
inline bool has_error() const
Check if an error is set.
See error_status and error_message for more details on the error.
Note
If there is an error reported in the status, the robot is not in an operational state anymore. Trying to append another action in the RobotFrontend will result in an exception in this case.
-
inline std::string get_error_message() const
Get the error message as std::string.
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name() override
-
inline virtual std::vector<std::vector<double>> get_data() override
Public Members
-
uint32_t action_repetitions = 0¶
Number of times the current action has been repeated.
If the back end wants to apply the next action but no new action was provided by the user in time, it may (depending on configuration) repeat the previous action. Each time this happens,
action_repetitions
is increased by one. Once a new action is provided, it will be reset to zero.See also next-action-not-in-time.
-
ErrorStatus error_status = ErrorStatus::NO_ERROR¶
Indicates if there is an error and, if yes, in which component.
See also
error_message for more information on the error.
See also
has_error()
Note
If there is an error reported in the status, the robot is not in an operational state anymore. Trying to append another action in the RobotFrontend will result in an exception in this case.
Public Static Attributes
-
static constexpr unsigned int ERROR_MESSAGE_LENGTH = 64¶
Maximum length of error messages (including terminating \0)
-
enum class ErrorStatus¶
-
template<typename Action_t, typename Observation_t>
struct RobotInterfaceTypes¶ - #include <types.hpp>
Public Types
-
typedef Observation_t Observation¶
-
typedef RobotBackend<Action, Observation> Backend¶
-
typedef RobotData<Action, Observation> BaseData¶
-
typedef SingleProcessRobotData<Action, Observation> SingleProcessData¶
-
typedef std::shared_ptr<SingleProcessData> SingleProcessDataPtr¶
-
typedef MultiProcessRobotData<Action, Observation> MultiProcessData¶
-
typedef std::shared_ptr<MultiProcessData> MultiProcessDataPtr¶
-
typedef RobotFrontend<Action, Observation> Frontend¶
-
typedef RobotLogEntry<Action, Observation> LogEntry¶
-
typedef RobotLogger<Action, Observation> Logger¶
-
typedef RobotBinaryLogReader<Action, Observation> BinaryLogReader¶
-
typedef Action_t Action
-
typedef Observation_t Observation
-
typedef RobotBackend<Action, Observation> Backend
-
typedef std::shared_ptr<Backend> BackendPtr
-
typedef RobotData<Action, Observation> BaseData
-
typedef std::shared_ptr<BaseData> BaseDataPtr
-
typedef SingleProcessRobotData<Action, Observation> SingleProcessData
-
typedef std::shared_ptr<SingleProcessData> SingleProcessDataPtr
-
typedef MultiProcessRobotData<Action, Observation> MultiProcessData
-
typedef std::shared_ptr<MultiProcessData> MultiProcessDataPtr
-
typedef RobotFrontend<Action, Observation> Frontend
-
typedef std::shared_ptr<Frontend> FrontendPtr
-
typedef RobotLogEntry<Action, Observation> LogEntry
-
typedef RobotLogger<Action, Observation> Logger
-
typedef RobotBinaryLogReader<Action, Observation> BinaryLogReader
-
typedef Observation_t Observation¶
-
namespace demo¶
-
class Action
- #include <types.hpp>
Actions to be performed by robot, will be received by Driver.
An action simply encapsulate two desired position value, one for each dof
Public Functions
-
inline void print(bool backline) const
-
template<class Archive>
inline void serialize(Archive &ar)
Public Members
-
int values[2]
-
inline void print(bool backline) const
-
class Action
-
namespace example¶
-
class Action : public robot_interfaces::Loggable, public robot_interfaces::Loggable
- #include <example.hpp>
Actions to be performed by robot, will be received by Driver.
An action simply encapsulate two desired position value, one for each DOF.
Public Functions
-
inline void print(bool backline)
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name()
-
inline virtual std::vector<std::vector<double>> get_data()
-
inline void print(bool backline)
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name()
-
inline virtual std::vector<std::vector<double>> get_data()
Public Members
-
int values[2]
-
inline void print(bool backline)
-
class Observation : public robot_interfaces::Loggable, public robot_interfaces::Loggable
- #include <example.hpp>
Observation read from the robot by Driver.
An observation is the current position for each DOF.
Public Functions
-
inline void print(bool backline)
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name()
-
inline virtual std::vector<std::vector<double>> get_data()
-
inline void print(bool backline)
-
template<class Archive>
inline void serialize(Archive &archive)
-
inline virtual std::vector<std::string> get_name()
-
inline virtual std::vector<std::vector<double>> get_data()
Public Members
-
int values[2]
-
inline void print(bool backline)
-
class Driver : public robot_interfaces::RobotDriver<Action, Observation>, public robot_interfaces::RobotDriver<Action, Observation>
- #include <example.hpp>
Send command to the robot and read observation from the robot. The DOF positions simply becomes the ones set by the latest action, capped between a min and a max value.
Public Functions
-
inline Driver(int min, int max)
-
inline virtual void initialize()
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
inline virtual Action apply_action(const Action &action_to_apply)
Apply action immediately and block until it is executed.
This method must apply the desired_action immediately when it is called, and only return once the action has been executed completely. This way we can accommodate both simulators and real robots with this interface.
- Parameters:
desired_action – The action we want to apply.
- Returns:
The action that was actually applied (since due to safety reasons it might not be possible to apply the desired action).
-
inline virtual Observation get_latest_observation()
Return the latest observation immediately.
- Returns:
-
inline virtual std::optional<std::string> get_error()
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
inline virtual void shutdown()
Shut down the robot safely.
Use this method if your robot needs to perform some action when shutting down, e.g. to move it to a defined rest position.
-
inline Driver(int min, int max)
-
inline virtual void initialize()
Initialize the robot.
Any initialization procedures that need to be done before sending actions to the robot should be done in this method (e.g. homing to find the absolute position).
-
inline virtual Action apply_action(const Action &action_to_apply)
Apply action immediately and block until it is executed.
This method must apply the desired_action immediately when it is called, and only return once the action has been executed completely. This way we can accommodate both simulators and real robots with this interface.
- Parameters:
desired_action – The action we want to apply.
- Returns:
The action that was actually applied (since due to safety reasons it might not be possible to apply the desired action).
-
inline virtual Observation get_latest_observation()
Return the latest observation immediately.
- Returns:
-
inline virtual std::optional<std::string> get_error()
Get error message if there is any error.
Uses std::optional for the return type, so an actual string only needs to be created if there is an error. This is relevant as std::string is in general not real-time safe and should thus be avoided. In case of an error this does not matter, as the control loop will be stopped anyway.
- Returns:
Returns an error message or std::nullopt if there is no error.
-
inline virtual void shutdown()
Shut down the robot safely.
Use this method if your robot needs to perform some action when shutting down, e.g. to move it to a defined rest position.
-
inline Driver(int min, int max)
-
class Action : public robot_interfaces::Loggable, public robot_interfaces::Loggable
-
typedef FingerTypes<1> MonoFingerTypes¶