C++ API and example¶
1. Introduction¶
This page exist in order to extract the examples from the Doxygen documentation, Please have look at the end of this page there are all the examples.
2. C++ API and example¶
-
class 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 : 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()
Public Members
-
int values[2]
-
inline void print(bool backline)
-
template<typename Types, typename = int>
struct BindTipForceIfExists - #include <pybind_helper.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:
BindTipForceIfExists<Types>::bind(pybind_class);
This is based on https://stackoverflow.com/a/16000226, see there for an explanation how/why this works.
Public Static Functions
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)
-
template<typename Types>
struct BindTipForceIfExists<Types, decltype((void)Types::Observation::tip_force, 0)> - #include <pybind_helper.hpp>
Public Static Functions
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)
-
static inline void bind(pybind11::class_<typename Types::Observation> &c)
-
class Driver : public robot_interfaces::RobotDriver<Action, Observation>
Public Functions
-
inline Driver()
-
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
Observation
-
inline virtual std::string get_error()
Get error message if there is any error.
- Returns
Returns an error message or an empty string 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.
Private Members
-
int state_[2]
Private Static Attributes
-
static const int MAX = 1000
-
static const int MIN = 0
-
inline Driver()
-
class Driver : 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::string get_error()
Get error message if there is any error.
- Returns
Returns an error message or an empty string 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.
Private Members
-
int state_[2]
-
int min_
-
int max_
-
inline Driver(int min, int max)
-
template<size_t N_FINGERS>
struct FingerTypes : 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::example::Action, robot_interfaces::example::Observation, robot_interfaces::NFingerObservation< N_FINGERS >, robot_interfaces::NJointAction< N >, robot_interfaces::NJointObservation< N >, robot_interfaces::Status
Public Functions
-
virtual std::vector<std::string> get_name() = 0
-
virtual std::vector<std::vector<double>> get_data() = 0
-
virtual std::vector<std::string> get_name() = 0
-
template<typename Driver>
class MonitoredRobotDriver : 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
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 virtual Driver::Action apply_action(const typename Driver::Action &desired_action) final
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()
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::Observation get_latest_observation()
Return the latest observation immediately.
- Returns
Observation
-
inline virtual std::string get_error()
Get error message if there is any error.
- Returns
Returns an error message or an empty string if there is no error.
-
inline virtual void shutdown() final
Shut down the robot safely.
After shutdown, actions sent by the user are ignored.
Private Functions
-
inline void loop()
Monitor the timing of action execution.
If one of the timing constrains is violated, the robot is immediately shut down.
Private Members
-
RobotDriverPtr robot_driver_
The actual robot driver.
-
double max_action_duration_s_
Max. time for executing an action.
-
double max_inter_action_duration_s_
Max. idle time between actions.
-
std::atomic<bool> is_shutdown_
Whether shutdown was initiated.
-
time_series::TimeSeries<bool> action_start_logger_
-
time_series::TimeSeries<bool> action_end_logger_
-
std::shared_ptr<real_time_tools::RealTimeThread> thread_
-
real_time_tools::SingletypeThreadsafeObject<std::string, 1> error_message_
Private Static Functions
-
static inline void *loop(void *instance_pointer)
-
template<typename Action, typename Observation>
class MultiProcessRobotData : 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)
-
template<typename Observation>
class MultiProcessSensorData : public robot_interfaces::SensorData<Observation> - #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)
-
template<size_t N_FINGERS>
struct NFingerObservation : 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
Public Functions
-
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 - #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 Types
-
typedef Eigen::Matrix<double, N, 1> Vector
Public Functions
-
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
sent_torque = torque + PD(position)
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.
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
-
Vector torque
Desired torque command (in addition to position controller).
-
Vector position
Desired position. Set to NaN to disable position controller.
-
Vector position_kp
P-gain for position controller. If NaN, default is used.
-
Vector position_kd
D-gain for position controller. If NaN, default is used.
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.
Public Static Attributes
-
static constexpr size_t num_joints = N
Number of joints.
-
template<size_t N>
struct NJointObservation : 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 Types
-
typedef Eigen::Matrix<double, N, 1> Vector
Public Functions
-
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
Public Static Attributes
-
static constexpr size_t num_joints = N
Number of joints.
-
class Observation : 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()
Public Members
-
int values[2]
-
inline void print(bool backline)
-
class Observation
- #include <types.hpp>
Read from the robot by Driver.
An observation is the current position 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
-
template<typename Action, typename Observation, typename Driver, typename Data = SingleProcessRobotData<Action, Observation>>
class Robot : 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>
-
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 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.
Private Functions
-
inline bool has_shutdown_request() const
-
inline void loop()
Main loop.
Iterate over robot_data_.desired_action and apply these actions to the robot, and read the applied_action and the observation from the robot and append them to the corresponding timeseries in robot_data_.
Private Members
-
std::shared_ptr<RobotDriver<Action, Observation>> robot_driver_
-
std::shared_ptr<RobotData<Action, Observation>> robot_data_
-
const bool real_time_mode_
Enable/disable real time mode.
If real time mode is enabled (true), the back end expects new actions to be provided in time by the user. If this does not happen, the last received action is repeated until the configured number of repetitions is exceeded in which case it stops with an error.
If real time mode is disabled (false), the back-end loop blocks and waits for the next action if it is not provided in time.
See also
-
const double first_action_timeout_
Timeout for the first action to arrive.
Timeout for the time between starting the backend loop and receiving the first action from the user. If exceeded, the backend shuts down. Set to infinity to disable the timeout.
-
const uint32_t max_number_of_actions_
Maximum number of actions that are executed by the backend.
If set to a value greater than zero, the backend will automatically shut down after the specified number of actions is executed.
-
std::atomic<bool> is_shutdown_requested_
Set to true when shutdown is requested.
This is used to notify the background loop about requested shutdown, so it terminates itself.
-
std::atomic<bool> loop_is_running_
Indicates if the background loop is still running.
-
uint32_t max_action_repetitions_
Number of times the previous action is repeated if no new one is provided.
-
real_time_tools::CheckpointTimer<6, false> timer_
-
real_time_tools::Timer frequency_timer_
Measure the duration of the control loop (for analysing time consistency).
-
std::shared_ptr<real_time_tools::RealTimeThread> thread_
-
std::atomic<int> termination_reason_
Private Static Functions
-
static inline void *loop(void *instance_pointer)
-
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
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.
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 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::SingleProcessRobotData< Action, Observation >
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.
Protected Functions
-
inline RobotData()
-
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 Functions
-
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::string get_error() = 0
Get error message if there is any error.
- Returns
Returns an error message or an empty string 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.
-
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 >
Public Types
-
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.
Protected Attributes
-
std::shared_ptr<RobotData<Action, Observation>> robot_data_
-
template<typename Action_t, typename Observation_t>
struct RobotInterfaceTypes - #include <types.hpp>
Public Types
-
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 Action_t Action
-
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)
Public Members
-
time_series::Index timeindex
-
time_series::Timestamp timestamp
-
Status_t status
-
Observation observation
-
Action desired_action
-
Action applied_action
-
template<class Archive>
-
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 write_current_buffer() or write_current_buffer_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.
Using start_continous_writing() and stop_continous_writing(): Deprecated! Run the logger in the background and write blocks of data directly to the log file while the robot is running (i.e. no buffering in memory is needed). This has the advantage that arbitrary time spans can be logged independent of the buffer size of the time series. Further in case of a software crash not all data will be lost but only the data since the last block was written. However, the permanent writing to a file puts some load on the system and may cause delays in the real-time critical robot code, thus causing the robot to shut down if timing constraints are violated. This method only supports uncompressed CSV as logfile format.
- Template Parameters
Public Types
-
enum class Format
Enumeration of possible log file formats.
Values:
-
enumerator BINARY
-
enumerator CSV
-
enumerator CSV_GZIP
-
enumerator BINARY
-
typedef RobotLogEntry<Action, Observation> LogEntry
Public Functions
Initialize logger.
- Parameters
robot_data – Pointer to the robot data instance.
block_size – Block size for writing data to the file when running the logger in the background.
-
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 start_continous_writing(const std::string &filename)
Start a thread to continuously log to file in the background.
See also
- Parameters
filename – The name of the log file. Existing files will be overwritten!
-
inline void stop_continous_writing()
Stop logging that was started with
start_continous_writing()
.Does nothing if logger is not currently running.
-
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()
beforewrite_current_buffer()
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 void write_current_buffer(const std::string &filename, long int start_index = 0, long int end_index = -1)
-
inline void write_current_buffer_binary(const std::string &filename, long int start_index = 0, long int end_index = -1)
Private Functions
-
inline std::vector<std::string> construct_header() const
To get the title of the log file, describing all the information that will be logged in it.
- Returns
header The title of the log file.
-
inline void append_names_to_header(const std::string &identifier, const std::vector<std::string> &field_name, const std::vector<std::vector<double>> &field_data, std::vector<std::string> &header) const
Fills in the name information of each field to be logged according to the size of the field.
- Parameters
identifier – The structure the field corresponds to
field_name – The name of the field
field_data – The field data
&header – Reference to the header of the log file
-
inline void write_header_to_file(const std::string &filename) const
Write CSV header to the log file.
This overwrites existing files!
-
inline void write_header_to_stream(std::ostream &output) const
Write CSV header to the output stream.
-
inline void append_robot_data_to_file(const std::string &filename, long int start_index, long int block_size)
Writes a block of time steps to the log file.
- Parameters
start_index – Time index marking the beginning of the block.
block_size – Number of time steps that are written to the log file.
-
inline void append_logger_buffer(std::ostream &output_stream) const
Appends the logger buffer as plain text (CSV) to an output stream.
- Parameters
output_stream – Output stream to which the log is written.
-
inline void append_field_data_to_file(const std::vector<std::vector<double>> &field_data, std::ostream &output_stream) const
Appends the data corresponding to every field at the same time index to the log file.
- Parameters
field_data – The field data
-
inline void save_buffer_binary(const std::string &filename) const
Save content of the internal buffer to a binary file.
- Parameters
filename – Path/name of the output file.
-
inline void save_buffer_text(const std::string &filename, bool use_gzip = false) const
Save content of the internal buffer to a CSV file.
- Parameters
filename – Path/name of the output file
use_gzip – If true, the output file is gzip-compressed.
-
inline void loop()
Writes everything to the log file.
It dumps all the data corresponding to block_size_ number of time indices at one go.
-
inline void buffer_loop()
Get observations from logger_data_ and add them to the buffer.
Private Members
-
std::thread thread_
-
std::shared_ptr<robot_interfaces::RobotData<Action, Observation>> logger_data_
-
std::vector<LogEntry> buffer_
-
size_t buffer_limit_
-
int block_size_
-
long int index_
-
std::atomic<bool> stop_was_called_
-
std::atomic<bool> enabled_
-
std::string output_file_name_
-
template<typename ObservationType>
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 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()
Private Functions
-
inline void loop()
Main loop.
Private Members
-
std::shared_ptr<SensorDriver<ObservationType>> sensor_driver_
-
std::shared_ptr<SensorData<ObservationType>> sensor_data_
-
bool shutdown_requested_
-
std::thread thread_
-
template<typename Observation>
class SensorData - #include <sensor_data.hpp>
Contains the data coming from the sensors.
- Template Parameters
Observation – Type of the sensor observation.
Subclassed by robot_interfaces::MultiProcessSensorData< Observation >, robot_interfaces::SingleProcessSensorData< Observation >
Public Members
-
std::shared_ptr<time_series::TimeSeriesInterface<Observation>> observation
Time series of the sensor observations.
Protected Functions
-
inline SensorData()
-
template<typename ObservationType>
class SensorDriver - #include <sensor_driver.hpp>
Base driver class from which all specific sensor drivers should derive.
- Template Parameters
ObservationType –
Public Functions
-
virtual ObservationType get_observation() = 0
return the observation
- Returns
depends on the observation structure of the sensor being interacted with
-
template<typename ObservationType>
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 time_series::Timestamp TimeStamp
-
typedef time_series::Index TimeIndex
Public Functions
-
inline ObservationType get_observation(const TimeIndex t) const
-
inline ObservationType get_latest_observation() const
-
inline TimeIndex get_current_timeindex() const
Private Members
-
std::shared_ptr<SensorData<ObservationType>> sensor_data_
-
template<typename Observation>
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>> 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.
Private Functions
-
inline void loop()
Get observations from sensor_data_ and add them to the buffer.
Private Members
-
DataPtr sensor_data_
-
std::vector<StampedObservation> buffer_
-
size_t buffer_limit_
-
std::thread buffer_thread_
-
bool enabled_
-
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
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.
Public Members
-
std::vector<Observation> data
Observations from the log file.
- Todo:
rename to “observations”
-
std::vector<double> timestamps
Timestamps of the time series from which the observations were logged.
-
template<size_t N>
struct SimpleNJointRobotTypes : 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 Action, typename Observation>
class SingleProcessRobotData : 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)
-
template<typename Observation>
class SingleProcessSensorData : public robot_interfaces::SensorData<Observation> - #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)
-
struct Status : 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
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.
-
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
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
Private Members
-
char error_message[ERROR_MESSAGE_LENGTH] = ""
Human-readable message describing the error.
Value is undefined if
error_status == NO_ERROR
.
-
enum class ErrorStatus
-
namespace robot_interfaces
Typedefs
-
typedef FingerTypes<1> MonoFingerTypes
-
typedef FingerTypes<3> TriFingerTypes
-
template<typename Type>
using Timeseries = time_series::TimeSeries<Type>
-
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
Functions
-
template<typename Types>
void create_python_bindings(pybind11::module &m) Create Python bindings for the specified 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_python_bindings<NJointRobotTypes<42>>(m); }
- Template Parameters
Types – An instance of NJointRobotTypes.
- Parameters
m – The second argument of the PYBIND11_MODULE macro.
-
template<typename ObservationType>
void create_sensor_bindings(pybind11::module &m) Create python bindings for different sensor types.
- Template Parameters
The – ObservationType
Variables
-
constexpr size_t JOINTS_PER_FINGER = 3
-
constexpr size_t BOARDS_PER_FINGER = 2
-
typedef FingerTypes<1> MonoFingerTypes
-
namespace demo
-
namespace example
- file demo.cpp
- #include “robot_interfaces/example.hpp”#include “robot_interfaces/monitored_robot_driver.hpp”#include “robot_interfaces/robot.hpp”#include “robot_interfaces/robot_backend.hpp”#include “robot_interfaces/robot_driver.hpp”#include “robot_interfaces/robot_frontend.hpp”#include “robot_interfaces/status.hpp”#include <memory>
Minimal demo of robot driver, backend and frontend.
- Author
Vincent Berenz license License BSD-3-Clause
- Copyright
Copyright (c) 2019, Max Planck Gesellschaft.
Functions
-
int main()
- file demo_multiprocess_backend.cpp
- #include <memory>#include “robot_interfaces/robot_backend.hpp”#include “robot_interfaces/robot_driver.hpp”#include “types.hpp”
Minimal demo of robot driver/backend running in its own process.
- Author
Vincent Berenz, Felix Widmaier license License BSD-3-Clause
- Copyright
Copyright (c) 2019-2020, Max Planck Gesellschaft.
Functions
-
int main()
- file demo_multiprocess_frontend.cpp
- #include <memory>#include “robot_interfaces/robot_frontend.hpp”#include “types.hpp”
Minimal demo of robot frontend running in its own process.
- Author
Vincent Berenz, Felix Widmaier license License BSD-3-Clause
- Copyright
Copyright (c) 2019-2020, Max Planck Gesellschaft.
Functions
-
int main()
- file types.hpp
Simple Action and Observation types that are used by some demos.
license License BSD-3-Clause
- Copyright
Copyright (c) 2019-2020, Max Planck Gesellschaft.
- file types.hpp
- #include <memory>#include “robot_backend.hpp”#include “robot_data.hpp”#include “robot_frontend.hpp”#include “robot_log_entry.hpp”#include “robot_log_reader.hpp”#include “robot_logger.hpp”
Observation of a Finger robot.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file example.hpp
- #include <unistd.h>#include <iostream>#include <vector>#include <robot_interfaces/loggable.hpp>#include <robot_interfaces/robot_driver.hpp>
Example driver and types for demo and testing purposes.
license License BSD-3-Clause
- Copyright
Copyright (c) 2019, Max Planck Gesellschaft.
- file finger_types.hpp
- #include <robot_interfaces/n_joint_robot_types.hpp>
- file loggable.hpp
- file monitored_robot_driver.hpp
- #include <atomic>#include <cmath>#include <iostream>#include <real_time_tools/process_manager.hpp>#include <real_time_tools/thread.hpp>#include <real_time_tools/threadsafe/threadsafe_object.hpp>#include <real_time_tools/timer.hpp>#include <time_series/time_series.hpp>#include <robot_interfaces/robot_driver.hpp>
- file n_finger_observation.hpp
- #include <string>#include <vector>#include <Eigen/Eigen>#include <serialization_utils/cereal_eigen.hpp>#include <robot_interfaces/loggable.hpp>
Observation of a Finger robot.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file n_joint_action.hpp
- #include <limits>#include <string>#include <vector>#include <Eigen/Eigen>#include <serialization_utils/cereal_eigen.hpp>#include <robot_interfaces/loggable.hpp>
Action of a generic n-joint robot.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file n_joint_observation.hpp
- #include <string>#include <vector>#include <Eigen/Eigen>#include <serialization_utils/cereal_eigen.hpp>#include <robot_interfaces/loggable.hpp>
Observation of a generic n-joint robot.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file n_joint_robot_types.hpp
- #include “n_finger_observation.hpp”#include “n_joint_action.hpp”#include “n_joint_observation.hpp”#include “types.hpp”
Types for an n-joint robot.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file pybind_helper.hpp
- #include <type_traits>#include <pybind11/eigen.h>#include <pybind11/pybind11.h>#include <pybind11/stl.h>#include <pybind11/stl_bind.h>#include <time_series/pybind11_helper.hpp>#include <robot_interfaces/robot_frontend.hpp>
Helper functions for creating Python bindings.
- License:
BSD 3-clause
- Copyright
2019, Max Planck Gesellschaft. All rights reserved.
- file robot.hpp
- #include <robot_interfaces/monitored_robot_driver.hpp>#include <robot_interfaces/robot_backend.hpp>#include <robot_interfaces/robot_data.hpp>#include <robot_interfaces/robot_frontend.hpp>#include <type_traits>
- file robot_backend.hpp
- #include <algorithm>#include <atomic>#include <cmath>#include <cstdint>#include <cstdlib>#include <pybind11/embed.h>#include <real_time_tools/checkpoint_timer.hpp>#include <real_time_tools/process_manager.hpp>#include <real_time_tools/thread.hpp>#include <signal_handler/signal_handler.hpp>#include <robot_interfaces/loggable.hpp>#include <robot_interfaces/robot_data.hpp>#include <robot_interfaces/robot_driver.hpp>#include <robot_interfaces/status.hpp>
- file robot_data.hpp
- #include <iostream>#include <memory>#include <string>#include <time_series/multiprocess_time_series.hpp>#include <time_series/time_series.hpp>#include “status.hpp”
RobotData classes for both single- and multi-process applications.
- License:
BSD 3-clause
- Copyright
Copyright (c) 2018-2020, New York University and Max Planck Gesellschaft
- file robot_driver.hpp
- #include <string>
- file robot_frontend.hpp
- #include <algorithm>#include <cmath>#include <robot_interfaces/robot_backend.hpp>#include <robot_interfaces/robot_data.hpp>#include <robot_interfaces/status.hpp>#include <time_series/time_series.hpp>
- file robot_log_entry.hpp
- #include <time_series/interface.hpp>#include <robot_interfaces/status.hpp>
- Copyright
Copyright (c) 2020, Max Planck Gesellschaft.
- file robot_log_reader.hpp
- #include <fstream>#include <vector>#include <cereal/archives/binary.hpp>#include <cereal/types/tuple.hpp>#include <cereal/types/vector.hpp>#include <serialization_utils/gzip_iostream.hpp>#include <robot_interfaces/robot_log_entry.hpp>#include <robot_interfaces/status.hpp>
API to read the data from a robot log file.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file robot_logger.hpp
- #include <atomic>#include <chrono>#include <fstream>#include <iostream>#include <iterator>#include <limits>#include <thread>#include <cereal/archives/binary.hpp>#include <cereal/types/tuple.hpp>#include <cereal/types/vector.hpp>#include <serialization_utils/gzip_iostream.hpp>#include <robot_interfaces/loggable.hpp>#include <robot_interfaces/robot_data.hpp>#include <robot_interfaces/robot_log_entry.hpp>#include <robot_interfaces/status.hpp>
- file pybind_sensors.hpp
- #include <pybind11/eigen.h>#include <pybind11/pybind11.h>#include <pybind11/stl.h>#include <robot_interfaces/sensors/sensor_backend.hpp>#include <robot_interfaces/sensors/sensor_data.hpp>#include <robot_interfaces/sensors/sensor_driver.hpp>#include <robot_interfaces/sensors/sensor_frontend.hpp>#include <robot_interfaces/sensors/sensor_logger.hpp>
Binds methods and objects to enable access from python.
- License:
BSD 3-clause
- Copyright
2020, New York University, Max Planck Gesellschaft. All rights reserved.
- file sensor_backend.hpp
- #include <algorithm>#include <cmath>#include <cstdint>#include <thread>#include <robot_interfaces/sensors/sensor_data.hpp>#include <robot_interfaces/sensors/sensor_driver.hpp>
Connects the driver with sensor data.
- License:
BSD 3-clause
- Copyright
2020, New York University, Max Planck Gesellschaft. All rights reserved.
- file sensor_data.hpp
- #include <iostream>#include <memory>#include <string>#include <time_series/multiprocess_time_series.hpp>#include <time_series/time_series.hpp>
To store all the data from all the sensors in use.
- License:
BSD 3-clause
- Copyright
2020, New York University, Max Planck Gesellschaft. All rights reserved.
- file sensor_driver.hpp
- #include <iostream>
Base driver for the sensors.
- License:
BSD 3-clause
- Copyright
2020, New York University, Max Planck Gesellschaft. All rights reserved.
- file sensor_frontend.hpp
- #include <algorithm>#include <cmath>#include <time_series/time_series.hpp>#include <robot_interfaces/sensors/sensor_data.hpp>
Consists of methods that are exposed to the user to interact with the sensors.
- License:
BSD 3-clause
- Copyright
2020, New York University, Max Planck Gesellschaft. All rights reserved.
- file sensor_log_reader.hpp
- #include <fstream>#include <vector>#include <cereal/archives/binary.hpp>#include <cereal/types/vector.hpp>#include <serialization_utils/gzip_iostream.hpp>
API to read the data from a sensor log file.
- License:
BSD 3-clause
- Copyright
2020, Max Planck Gesellschaft. All rights reserved.
- file sensor_logger.hpp
- #include <atomic>#include <fstream>#include <memory>#include <thread>#include <vector>#include <cereal/archives/binary.hpp>#include <cereal/types/tuple.hpp>#include <cereal/types/vector.hpp>#include <serialization_utils/gzip_iostream.hpp>#include “sensor_data.hpp”
- file status.hpp
- #include <cereal/types/string.hpp>#include <robot_interfaces/loggable.hpp>#include <string>#include <vector>
Defines the Status struct.
- file py_finger_types.cpp
- #include <robot_interfaces/finger_types.hpp>#include <robot_interfaces/pybind_helper.hpp>
Create bindings for One-Joint robot types.
Functions
-
PYBIND11_MODULE(py_finger_types, m)
-
PYBIND11_MODULE(py_finger_types, m)
- file py_generic.cpp
- #include <time_series/pybind11_helper.hpp>#include <robot_interfaces/pybind_helper.hpp>#include <robot_interfaces/robot_backend.hpp>#include <robot_interfaces/status.hpp>
Create Python bindings for generic types.
- License:
BSD 3-clause
- Copyright
2019, Max Planck Gesellschaft. All rights reserved.
Functions
-
PYBIND11_MODULE(py_generic, m)
- file py_one_joint_types.cpp
- #include <robot_interfaces/n_joint_robot_types.hpp>#include <robot_interfaces/pybind_helper.hpp>
Create bindings for One-Joint robot types.
Functions
-
PYBIND11_MODULE(py_one_joint_types, m)
-
PYBIND11_MODULE(py_one_joint_types, m)
- file py_solo_eight_types.cpp
- #include <robot_interfaces/n_joint_robot_types.hpp>#include <robot_interfaces/pybind_helper.hpp>
Create bindings for Solo8 robot types.
Functions
-
PYBIND11_MODULE(py_solo_eight_types, m)
-
PYBIND11_MODULE(py_solo_eight_types, m)
- file py_trifinger_types.cpp
- #include <robot_interfaces/finger_types.hpp>#include <robot_interfaces/pybind_helper.hpp>
Create bindings for TriFinger robot types.
Functions
-
PYBIND11_MODULE(py_trifinger_types, m)
-
PYBIND11_MODULE(py_trifinger_types, m)
- file py_two_joint_types.cpp
- #include <robot_interfaces/n_joint_robot_types.hpp>#include <robot_interfaces/pybind_helper.hpp>
Create bindings for Two-Joint robot types.
Functions
-
PYBIND11_MODULE(py_two_joint_types, m)
-
PYBIND11_MODULE(py_two_joint_types, m)
- page todo
- Member robot_interfaces::MultiProcessRobotData< Action, Observation >::MultiProcessRobotData (const std::string &shared_memory_id_prefix, bool is_master, size_t history_length=1000)
Make this constructor protected and implement factory methods like in MultiprocessTimeSeries..
- Member robot_interfaces::SensorLogReader< Observation >::data
rename to “observations”
- page deprecated
- Member robot_interfaces::RobotLogger< Action, Observation >::start_continous_writing (const std::string &filename)
- page license
- File n_finger_observation.hpp
BSD 3-clause
- File n_joint_action.hpp
BSD 3-clause
- File n_joint_observation.hpp
BSD 3-clause
- File n_joint_robot_types.hpp
BSD 3-clause
- File py_generic.cpp
BSD 3-clause
- File pybind_helper.hpp
BSD 3-clause
- File pybind_sensors.hpp
BSD 3-clause
- File robot_data.hpp
BSD 3-clause
- File robot_log_reader.hpp
BSD 3-clause
- File sensor_backend.hpp
BSD 3-clause
- File sensor_data.hpp
BSD 3-clause
- File sensor_driver.hpp
BSD 3-clause
- File sensor_frontend.hpp
BSD 3-clause
- File sensor_log_reader.hpp
BSD 3-clause
- File types.hpp
BSD 3-clause
- dir demos
- dir include
- dir include/robot_interfaces
- dir include/robot_interfaces/sensors
- dir srcpy
- example demo.cpp
This demo shows robot_interfaces of a dummy “2dof” robot, in which a dof “position” is represented by an integer.
This demo shows robot_interfaces of a dummy “2dof” robot, in which a dof “position” is represented by an integer
#include "robot_interfaces/example.hpp" #include "robot_interfaces/monitored_robot_driver.hpp" #include "robot_interfaces/robot.hpp" #include "robot_interfaces/robot_backend.hpp" #include "robot_interfaces/robot_driver.hpp" #include "robot_interfaces/robot_frontend.hpp" #include "robot_interfaces/status.hpp" #include <memory> using namespace robot_interfaces::example; int main() { typedef robot_interfaces::RobotBackend<Action, Observation> Backend; typedef robot_interfaces::SingleProcessRobotData<Action, Observation> Data; typedef robot_interfaces::RobotFrontend<Action, Observation> Frontend; // max time allowed for the robot to apply an action. double max_action_duration_s = 0.02; // max time between for 2 successive actions double max_inter_action_duration_s = 0.05; // demo showing the separated usage of backend and frontend { std::cout << "\n -- * -- Frontend and Backend -- * --\n" << std::endl; std::shared_ptr<Driver> driver_ptr = std::make_shared<Driver>(0, 1000); // Wrap the driver in a MonitoredRobotDriver to automatically run a // timing watchdog. If timing is violated, the robot will immediately // be shut down. // If no time monitoring is needed in your application, you can simply // use the `driver_ptr` directly, without the wrapper. auto monitored_driver_ptr = std::make_shared<robot_interfaces::MonitoredRobotDriver<Driver>>( driver_ptr, max_action_duration_s, max_inter_action_duration_s); std::shared_ptr<Data> data_ptr = std::make_shared<Data>(); Backend backend(monitored_driver_ptr, data_ptr); backend.initialize(); Frontend frontend(data_ptr); Action action; Observation observation; // simulated action : // 1 dof going from 200 to 300 // The other going from 300 to 200 for (uint value = 200; value <= 300; value++) { action.values[0] = value; action.values[1] = 500 - value; // this action will be stored at index robot_interfaces::TimeIndex index = frontend.append_desired_action(action); // getting the observation corresponding to the applied // action, i.e. at the same index observation = frontend.get_observation(index); std::cout << "value: " << value << " | "; action.print(false); observation.print(true); } } // demo representing usage of frontend and backend // encapsulated in the same instance { std::cout << "\n -- * -- Robot -- * --\n" << std::endl; typedef robot_interfaces::Robot<Action, Observation, Driver> Robot; int min = 0; int max = 100; Robot robot( max_action_duration_s, max_inter_action_duration_s, min, max); robot.initialize(); Action action; Observation observation; // simulated action : // 1 dof going from 200 to 300 // The other going from 300 to 200 for (uint value = 200; value <= 300; value++) { action.values[0] = value; action.values[1] = 500 - value; // this action will be stored at index robot_interfaces::TimeIndex index = robot.append_desired_action(action); // getting the observation corresponding to the applied // action, i.e. at the same index observation = robot.get_observation(index); std::cout << "value: " << value << " | "; action.print(false); observation.print(true); } } }
- example demo_multiprocess_backend.cpp
Robot backend for a dummy “2dof” robot in a multi process setup.
Robot backend for a dummy “2dof” robot in a multi process setup.
#include <memory> #include "robot_interfaces/robot_backend.hpp" #include "robot_interfaces/robot_driver.hpp" #include "types.hpp" using namespace robot_interfaces::demo; // TODO put driver in separate file so no duplication to demo.cpp? Discuss // with Vincent. // 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 (0 and 1000) class Driver : public robot_interfaces::RobotDriver<Action, Observation> { public: Driver() { } // at init dof are at min value void initialize() { state_[0] = Driver::MIN; state_[1] = Driver::MIN; } // just clip desired values // between 0 and 1000 Action apply_action(const Action &action_to_apply) { std::cout << "received action "; action_to_apply.print(true); Action applied; for (unsigned int i = 0; i < 2; i++) { if (action_to_apply.values[i] > Driver::MAX) { applied.values[i] = Driver::MAX; } else if (action_to_apply.values[i] < Driver::MIN) { applied.values[i] = Driver::MIN; } else { applied.values[i] = action_to_apply.values[i]; } // simulating the time if could take for a real // robot to perform the action usleep(1000); state_[i] = applied.values[i]; } return applied; } Observation get_latest_observation() { Observation observation; observation.values[0] = state_[0]; observation.values[1] = state_[1]; return observation; } std::string get_error() { return ""; // no error } void shutdown() { // nothing to do } private: int state_[2]; const static int MAX = 1000; const static int MIN = 0; }; int main() { typedef robot_interfaces::RobotBackend<Action, Observation> Backend; typedef robot_interfaces::MultiProcessRobotData<Action, Observation> MultiProcessData; auto driver_ptr = std::make_shared<Driver>(); // the backend process acts as master for the shared memory auto data_ptr = std::make_shared<MultiProcessData>("multiprocess_demo", true); Backend backend(driver_ptr, data_ptr); backend.initialize(); // TODO would be nicer to check if backend loop is still running while (true) { } }
- example demo_multiprocess_frontend.cpp
Robot frontend for a dummy “2dof” robot in a multi process setup.
Robot frontend for a dummy “2dof” robot in a multi process setup.
#include <memory> #include "robot_interfaces/robot_frontend.hpp" #include "types.hpp" using namespace robot_interfaces::demo; int main() { typedef robot_interfaces::RobotFrontend<Action, Observation> Frontend; typedef robot_interfaces::MultiProcessRobotData<Action, Observation> MultiProcessData; // The shared memory is managed by the backend process, so set the // is_master argument to false. auto data_ptr = std::make_shared<MultiProcessData>("multiprocess_demo", false); Frontend frontend(data_ptr); Action action; Observation observation; // simulated action : // 1 dof going from 200 to 300 // The other going from 300 to 200 for (uint value = 200; value <= 300; value++) { action.values[0] = value; action.values[1] = 500 - value; // this action will be stored at index robot_interfaces::TimeIndex index = frontend.append_desired_action(action); // getting the observation corresponding to the applied // action, i.e. at the same index observation = frontend.get_observation(index); std::cout << "value: " << value << " | "; action.print(false); observation.print(true); } }