monopod_drivers C++ API

namespace monopod_drivers

This namespace is the standard namespace of the package.

Typedefs

typedef time_series::TimeSeries<double> ScalarTimeseries

A useful shortcut.

Type defs

typedef time_series::Index Index

A useful shortcut.

typedef time_series::TimeSeries<Index> IndexTimeseries

A useful shortcut.

template<typename Type>
using Ptr = std::shared_ptr<Type>

This is a shortcut for creating shared pointer in a simpler writing expression.

Template Parameters

Type – is the template parameter of the shared pointer.

template<typename Type>
using Vector = std::vector<Type>

A useful shortcut.

Enums

enum JointNamesIndex

Enumerates the joint names for indexing.

Values:

enumerator hip_joint
enumerator knee_joint
enumerator boom_connector_joint
enumerator planarizer_yaw_joint
enumerator planarizer_pitch_joint
enum Measurements

Here is a list of the different measurement available on the blmc card.

Values:

enumerator position
enumerator velocity
enumerator acceleration
enumerator current
enumerator encoder_index
enumerator measurement_count
enum Mode

Mode defines the boards (joints) that are being considered from the canbus. This allows us to handle say only wanting to use the leg or only wanting to read plnarizer sensors. Also defines diferent task modes for the gym environment.

Values:

enumerator FREE

Complete free boom connector (5 joints total)

enumerator FIXED_CONNECTOR

Fixed boom connector (4 joints total)

enumerator FIXED

Fixed boom connector and planrizer yaw (3 joints total)

enumerator MOTOR_BOARD

motor board

enumerator ENCODER_BOARD1

encoder board 1

enumerator ENCODER_BOARD2

encoder board 2

enum HomingReturnCode

Possible return values of the homing.

Values:

enumerator NOT_INITIALIZED

Homing was not initialized and can therefore not be performed.

enumerator RUNNING

Homing is currently running.

enumerator SUCCEEDED

Homing is succeeded.

enumerator FAILED

Homing failed.

enum GoToReturnCode

Possible return values of the go_to.

Values:

enumerator RUNNING

GoTo is currently running.

enumerator SUCCEEDED

Position has been reached succeeded.

enumerator FAILED

Robot is stuck(hit an obstacle) before reaching its final position.

Functions

template<typename Type>
std::vector<std::shared_ptr<Type>> create_vector_of_pointers(const size_t &size, const size_t &length)

Create a vector of pointers.

Template Parameters

Type – of the data

Parameters
  • size – is number of pointers to be created.

  • length – is the dimension of the data arrays.

Returns

Vector<Ptr<Type>> which is the a list of list of data of type Type

class BoardStatus
#include <boards.hpp>

This class represent a 8 bits message that describe the state (enable/disabled) of the card and the two motors or that of the car and 2 encoders.

Public Types

enum ErrorCodes

This is the list of the error codes.

Values:

enumerator NONE

No error.

enumerator ENCODER

Encoder error too high.

enumerator CAN_RECV_TIMEOUT

Timeout for receiving current references exceeded.

enumerator CRIT_TEMP

Motor temperature reached critical value.

Note

This is currently unused as no temperature sensing is done.

enumerator POSCONV

Some error in the SpinTAC Position Convert module.

enumerator POS_ROLLOVER

Position Rollover occured.

enumerator OTHER

Some other error.

Public Functions

inline void print() const

Simply print the status of the motor board.

inline bool is_ready() const

Check if the all status are green.

inline uint8_t get_error_code() const

Check if the all status are green.

inline std::string get_error_description() const

Get a human-readable description of the error code.

Public Members

uint8_t error_code

This encodes the error codes. deault is 0 which is no code.

These are the list of bits of the message.

uint8_t system_enabled

Bits 0 enables/disable of the system (motor board).

uint8_t motor1_enabled

Bits 1 enables/disable of the motor 1.

uint8_t motor1_ready

Bits 2 checks if the motor 1 is ready or not.

uint8_t motor2_enabled

Bits 3 enables/disable of the motor 2.

uint8_t motor2_ready

Bits 4 checks if the motor 2 is ready or not.

class CanBus : public monopod_drivers::CanBusInterface
#include <can_bus.hpp>

CanBus is the implementation of the CanBusInterface.

Public Functions

CanBus(const std::string &can_interface_name, const size_t &history_length = 1000)

Construct a new CanBus object.

Parameters
  • can_interface_name

  • history_length

virtual ~CanBus()

Destroy the CanBus object.

inline virtual std::shared_ptr<const CanframeTimeseries> get_output_frame() const

Get the output frame.

Getters

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual std::shared_ptr<const CanframeTimeseries> get_input_frame()

Get the input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual std::shared_ptr<const CanframeTimeseries> get_sent_input_frame()

Get the input frame thas has been sent.

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual void set_input_frame(const CanBusFrame &input_frame)

Setters.

Set the input frame

Parameters

input_frame

virtual void send_if_input_changed()

Sender.

Send the queue of message to the can network

class CanBusConnection
#include <can_bus.hpp>

CanBusConnection is a data structure that contains the hardware details for the connection between to can cards.

Public Members

struct sockaddr_can send_addr

send_addr is the ip address where to send the the messages.

int socket

socket is the port through which the messages will be processed

class CanBusControlBoards : public monopod_drivers::ControlBoardsInterface
#include <boards.hpp>

This class CanBusControlBoards implements a ControlBoardsInterface specific to CAN networks.

Public Functions

CanBusControlBoards(std::shared_ptr<CanBusInterface> can_bus, const size_t &history_length = 1000, const int &control_timeout_ms = 100)

Construct a new CanBusControlBoards object.

Parameters
  • can_bus

  • history_length

~CanBusControlBoards()

Destroy the CanBusControlBoards object.

inline virtual Ptr<const ScalarTimeseries> get_measurement(const int &index) const

Get the measurement data.

Getters

Parameters

index – is the kind of measurement we are insterested in.

Returns

Ptr<const ScalarTimeseries> is the list of the last measurements acquiered from the CAN card.

inline virtual Ptr<const StatusTimeseries> get_status(const int &index) const

Get the status of the CAN card.

Parameters

index – the kind of status we are interested in.

Returns

Ptr<const StatusTimeseries> is the list of last acquiered status.

inline virtual Ptr<const ScalarTimeseries> get_control(const int &index) const

Get the controls to be sent.

Parameters

index – the kind of control we are interested in.

Returns

Ptr<const ScalarTimeseries> is the list of the control to be sent.

inline virtual Ptr<const CommandTimeseries> get_command() const

Get the commands to be sent.

Returns

Ptr<const CommandTimeseries> is the list of the command to be sent.

inline virtual Ptr<const ScalarTimeseries> get_sent_control(const int &index) const

Get the already sent controls.

Parameters

index – the kind of control we are interested in.

Returns

Ptr<const ScalarTimeseries> is the list of the sent cotnrols.

inline virtual Ptr<const CommandTimeseries> get_sent_command() const

Get the already sent commands.

Returns

Ptr<const CommandTimeseries> is the list of the sent cotnrols.

virtual void set_active_board(const int &index)

Set a board to an active state if it is not already active. This means the board will now have its status checked for is_ready and if the board is the motor_board we must send enable the motors etc.

Setters

Parameters

index

inline virtual void set_control(const double &control, const int &index)

Set the controls, see ControlBoardsInterface::set_control.

Parameters
  • control

  • index

inline virtual void set_command(const ControlBoardsCommand &command)

Set the commands, see ControlBoardsInterface::set_command.

Parameters

command

virtual void send_if_input_changed()

Send the actual command and controls.

virtual void wait_until_ready()

returns only once board and motors are ready.

virtual void reset()

This will cause the control to reset the “safemode” if the control is currently in safemode. Additionally the motors will be paused and The control boards will be reset such that any timed out connection will be reestablished.

inline virtual void enter_safemode()

This will cause the control to be forced into a “safemode” where the control is set to zero then held constant until reset.

inline virtual bool is_safemode()

This will return if the control is in “safemode”.

bool is_ready()

True if all active boards have established at least one status message from the board that does not include any error.

void pause_motors()

Sets motors to Idle and sets the canbus control recieve timeout on board to none until next action is sent.

void disable_can_recv_timeout()

Disable the can reciever timeout.

class CanBusFrame
#include <can_bus.hpp>

CanBusFrame is a class that contains a fixed sized amount of data to be send or received via the can bus.

Public Members

std::array<uint8_t, 8> data

data is the acutal data to be sent/received.

uint8_t dlc

dlc is the size of the message.

can_id_t id

id is the id number return by the CAN bus.

class CanBusInterface : public monopod_drivers::DeviceInterface
#include <can_bus.hpp>

CanBusInterface is an abstract class that defines an API for the communication via Can bus.

Subclassed by monopod_drivers::CanBus

Public Types

typedef time_series::TimeSeries<CanBusFrame> CanframeTimeseries

CanframeTimeseries is a simple sohortcut.

Public Functions

inline virtual ~CanBusInterface()

Destroy the CanBusInterface object.

virtual std::shared_ptr<const CanframeTimeseries> get_output_frame() const = 0

Get the output frame.

getters

Returns

std::shared_ptr<const CanframeTimeseries>

virtual std::shared_ptr<const CanframeTimeseries> get_input_frame() = 0

Get the input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

virtual std::shared_ptr<const CanframeTimeseries> get_sent_input_frame() = 0

Get the sent input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

virtual void set_input_frame(const CanBusFrame &input_frame) = 0

Set the input frame saves the input frame to be sent in a queue.

setters

Parameters

input_frame

virtual void send_if_input_changed() = 0

send all the input frame to the can network

Sender

class ControlBoardsCommand
#include <boards.hpp>

This ControlBoardsCommand class is a data structurs that defines a command to the monopod_drivers::ControlBoardsInterface::BoardIndex boards.

Public Types

enum IDs

IDs are the different implemented commands that one can send to the ControlBoards.

Values:

enumerator ENABLE_SYS
enumerator ENABLE_MTR1
enumerator ENABLE_MTR2
enumerator ENABLE_VSPRING1
enumerator ENABLE_VSPRING2
enumerator SEND_CURRENT
enumerator SEND_POSITION
enumerator SEND_VELOCITY
enumerator SEND_ADC6
enumerator SEND_ENC_INDEX
enumerator SEND_ALL
enumerator SET_CAN_RECV_TIMEOUT
enumerator ENABLE_POS_ROLLOVER_ERROR
enum Contents

Is the different command status.

Values:

enumerator ENABLE
enumerator DISABLE

Public Functions

inline ControlBoardsCommand()

Construct a new ControlBoardsCommand object.

inline ControlBoardsCommand(uint32_t id, int32_t content)

Construct a new ControlBoardsCommand object.

Parameters
  • id – defines the command to apply.

  • content – defines of the command is enabled or disabled.

inline void print() const

Display on a terminal the status of the message.

Public Members

uint32_t id_

id_ is the command to be modifies on the card.

int32_t content_

content_ is the value of teh command to be sent to the cards.

class ControlBoardsInterface : public monopod_drivers::DeviceInterface
#include <boards.hpp>

ControlBoardsInterface declares an API to inacte with a ControlBoards.

Subclassed by monopod_drivers::CanBusControlBoards, monopod_drivers::DummyControlBoards

Public Types

enum MeasurementIndex

This is the list of the measurement we can access.

Values:

enumerator current_0

Current for the hip joint

enumerator current_1

Current for the knee joint

enumerator position_0

Position of the hip joint

enumerator position_1

Position of the knee joint

enumerator position_2

Position of the planarizer pitch joint

enumerator position_3

Position of the planarizer yaw joint

enumerator position_4

Position of the boom connector joint

enumerator velocity_0

Velocity of the hip joint

enumerator velocity_1

Velocity of the knee joint

enumerator velocity_2

Velocity of the planarizer pitch joint

enumerator velocity_3

Velocity of the planarizer yaw joint

enumerator velocity_4

Velocity of the boom connector joint

enumerator acceleration_0

Acceleration of the hip joint

enumerator acceleration_1

Acceleration of the knee joint

enumerator acceleration_2

Acceleration of the planarizer pitch joint

enumerator acceleration_3

Acceleration of the planarizer yaw joint

enumerator acceleration_4

Acceleration of the boom connector joint

enumerator encoder_index_0

encoder index (number of encoder rotations from 0) of the hip joint

enumerator encoder_index_1

encoder index (number of encoder rotations from 0) of the knee joint

enumerator encoder_index_2

encoder index (number of encoder rotations from 0) of the planarizer pitch joint

enumerator encoder_index_3

encoder index (number of encoder rotations from 0) of the planarizer yaw joint

enumerator encoder_index_4

encoder index (number of encoder rotations from 0) of the boom connector joint

enumerator analog_0
enumerator analog_1
enumerator measurement_count
enum BoardIndex

This is the list of the measurement we can access.

Values:

enumerator motor_board

Motor board is the board with the motors for the planarizer leg. This board must e flashed with the proper firmware.

enumerator encoder_board1

Encoder board 1 is the board with the planarizer yaw and pitch joints encoders. Index 0 will be pitch and index 1 is yaw.

enumerator encoder_board2

Encoder board 2 is the board with the boom connector joint. Index 0 is where encoder should be located

enumerator board_count

this shows the number of boards when converteed to an int.

enum ControlIndex

This is the list of the controls we can send.

Values:

enumerator current_target_0

Current for the hip joint

enumerator current_target_1

Current for the knee joint

enumerator control_count

This shows the number of current targets when converteed to an int.

typedef time_series::TimeSeries<BoardStatus> StatusTimeseries

A useful shortcut.

typedef time_series::TimeSeries<ControlBoardsCommand> CommandTimeseries

A useful shortcut.

Public Functions

inline virtual ~ControlBoardsInterface()

Destroy the ControlBoardsInterface object.

virtual Ptr<const ScalarTimeseries> get_measurement(const int &index) const = 0

Get the measurements.

Getters

Parameters

index – is the kind of measurement we are looking for.

Returns

Ptr<const ScalarTimeseries> is the list of the last time stamped measurement acquiered.

virtual Ptr<const StatusTimeseries> get_status(const int &index) const = 0

Get the status of one of the boards.

Parameters

index – the kind of status we are interested in.

Returns

Ptr<const StatusTimeseries> is the list of the last status of the card.

virtual Ptr<const ScalarTimeseries> get_control(const int &index) const = 0

Get the controls to be send.

input logs

Parameters

index – define the kind of control we are looking for.

Returns

Ptr<const ScalarTimeseries> is the list of the controls to be send.

virtual Ptr<const CommandTimeseries> get_command() const = 0

Get the commands to be send.

Returns

Ptr<const CommandTimeseries> is the list of the commands to be send.

virtual Ptr<const ScalarTimeseries> get_sent_control(const int &index) const = 0

Get the sent controls.

Parameters

index – define the kind of control we are looking for.

Returns

Ptr<const ScalarTimeseries> is the list of the controls sent recently.

virtual Ptr<const CommandTimeseries> get_sent_command() const = 0

Get the sent commands.

Returns

Ptr<const CommandTimeseries> is the list of the commands sent recently.

virtual void set_active_board(const int &index) = 0

Set a board to an active state if it is not already active. This means the board will now have its status checked for is_ready and if the board is the motor_board we must send enable the motors etc.

Setters

Parameters

index

virtual void set_control(const double &control, const int &index) = 0

set_control save the control internally. In order to actaully send the controls to the network please call “send_if_input_changed”

Parameters
  • control – is the value of the control.

  • index – define the kind of control we want to send.

virtual void set_command(const ControlBoardsCommand &command) = 0

set_command save the command internally. In order to actaully send the controls to the network please call “send_if_input_changed”

Parameters

command – is the command to be sent.

virtual void send_if_input_changed() = 0

Actually send the commands and the controls.

virtual void wait_until_ready() = 0

returns only once board and motors are ready.

virtual void enter_safemode() = 0

This will cause the control to be forced into a “safemode” where the control is set to zero then held constant until reset.

virtual bool is_safemode() = 0

This will return if the control is in “safemode”.

virtual void reset() = 0

This will cause the control to reset the “safemode” if the control is currently in safemode. Additionally the motors will be paused and The control boards will be reset such that any timed out connection will be reestablished.

class DeviceInterface
#include <device_interface.hpp>

this class exists purely for logical reasons, it does not in itself implement anything.

the purpose of this class is to provide guidelines how a device should be implemented. any device has a number of inputs and outputs, see the following diagram for an example with two inputs and outputs.

generally, we expect the following functions to be implemented:

  • a set function for each input (several inputs may share a set function which takes an index argument).

  • a send_if_input_changed() function which will send the inputs to the device if any of them have changed.

  • functions to access the current inputs and outputs, as well as the inputs which have been sent to the device. Rather than just returning the latest elements, these function should return a time series of these objects, such that the user can synchronize (e.g. wait for the next element or step through them one by one such that none of them is missed)

../_images/device_class_diagram.svg

Subclassed by monopod_drivers::CanBusInterface, monopod_drivers::ControlBoardsInterface, monopod_drivers::EncoderInterface

class DummyControlBoards : public monopod_drivers::ControlBoardsInterface
#include <boards.hpp>

This class DummyControlBoards implements a ControlBoardsInterface specific to CAN networks.

Public Functions

inline DummyControlBoards()

Construct a new DummyControlBoards object.

inline ~DummyControlBoards()

Destroy the DummyControlBoards object.

inline virtual Ptr<const ScalarTimeseries> get_measurement(const int &index) const

Get the measurement data.

Getters

Parameters

index – is the kind of measurement we are insterested in.

Returns

Ptr<const ScalarTimeseries> is the list of the last measurements acquiered from the CAN card.

inline virtual Ptr<const StatusTimeseries> get_status(const int &index) const

Get the status of the CAN card.

Parameters

index – the kind of status we are interested in.

Returns

Ptr<const StatusTimeseries> is the list of last acquiered status.

inline virtual Ptr<const ScalarTimeseries> get_control(const int &index) const

Get the controls to be sent.

Parameters

index – the kind of control we are interested in.

Returns

Ptr<const ScalarTimeseries> is the list of the control to be sent.

inline virtual Ptr<const CommandTimeseries> get_command() const

Get the commands to be sent.

Returns

Ptr<const CommandTimeseries> is the list of the command to be sent.

inline virtual Ptr<const ScalarTimeseries> get_sent_control(const int &index) const

Get the already sent controls.

Parameters

index – the kind of control we are interested in.

Returns

Ptr<const ScalarTimeseries> is the list of the sent cotnrols.

inline virtual Ptr<const CommandTimeseries> get_sent_command() const

Get the already sent commands.

Returns

Ptr<const CommandTimeseries> is the list of the sent cotnrols.

inline virtual void set_active_board(const int &index)

Set a board to an active state if it is not already active. This means the board will now have its status checked for is_ready and if the board is the motor_board we must send enable the motors etc.

Setters

Parameters

index

inline virtual void set_control(const double &control, const int &index)

Set the controls, see ControlBoardsInterface::set_control.

Parameters
  • control

  • index

inline virtual void set_command(const ControlBoardsCommand &command)

Set the commands, see ControlBoardsInterface::set_command.

Parameters

command

inline virtual void send_if_input_changed()

Send the actual command and controls.

inline virtual void wait_until_ready()

returns only once board and motors are ready.

inline virtual void reset()

This will cause the control to reset the “safemode” if the control is currently in safemode. Additionally the system will be set to idle with no timeout on communication.

inline virtual void enter_safemode()

This will cause the control to be forced into a “safemode” where the control is set to zero then held constant until reset.

inline virtual bool is_safemode()

This will return if the control is in “safemode”.

Public Members

Vector<Ptr<ScalarTimeseries>> measurement_

measurement_ contains all the measurements acquiered from the CAN board.

Vector<Ptr<StatusTimeseries>> status_

This is the status history of the CAN board.

Vector<Ptr<ScalarTimeseries>> control_

This is the buffer of the controls to be sent to card.

Vector<Ptr<ScalarTimeseries>> sent_control_

This is the history of the already sent controls.

bool is_safemode_ = false

Is the system in safemode? This implies the motors were killed and now being held constant at 0 control magnitude. This is maintained until reset.

class Encoder : public monopod_drivers::EncoderInterface
#include <encoder.hpp>

This class implements the EncoderInterface.

Subclassed by monopod_drivers::Motor

Public Functions

Encoder(Ptr<ControlBoardsInterface> board, JointNamesIndex encoder_id)

Construct a new Encoder object.

Parameters
  • board – is the EncoderBoard to be used.

  • encoder_id – is the id of the motor on the on-board card

inline virtual ~Encoder()

Destroy the Encoder object.

virtual Ptr<const ScalarTimeseries> get_measurement(const Measurements &index) const

Get the measurements.

Getters

Parameters

index – is the kind of measurement we are instersted in. see Measurements.

Returns

Ptr<const ScalarTimeseries> The history of the measurement

virtual Ptr<const StatusTimeseries> get_status() const

Get the status.

Returns

Ptr<const StatusTimeseries> the pointer to the desired status history.

virtual void print() const

Print the motor status and state.

class EncoderInterface : public monopod_drivers::DeviceInterface
#include <encoder.hpp>

This class declares an interface to the motor. It allows the user to access the sensors data as well as sending controls. The only control supported for now is the current.

Subclassed by monopod_drivers::Encoder, monopod_drivers::MotorInterface

Public Types

typedef time_series::TimeSeries<BoardStatus> StatusTimeseries

A useful shortcut.

typedef ControlBoardsInterface::BoardIndex BoardIndex

A useful shortcut.

Public Functions

inline virtual ~EncoderInterface()

Destroy the EncoderInterface object.

virtual Ptr<const ScalarTimeseries> get_measurement(const Measurements &index) const = 0

Get the measurements.

Getters

Parameters

index

Returns

Ptr<const ScalarTimeseries> the pointer to the desired measurement history.

virtual Ptr<const StatusTimeseries> get_status() const = 0

Get the status.

Parameters

index

Returns

Ptr<const StatusTimeseries> the pointer to the desired status history.

virtual void print() const = 0

Print the motor status and state.

class EncoderJointModule
#include <encoder_joint_module.hpp>

The EncoderJointModule class is containing the joint information. It is here to help converting the data from the encoder side to the joint side. It also allows the calibration of the joint position during initialization.

Subclassed by monopod_drivers::MotorJointModule

Public Functions

EncoderJointModule(JointNamesIndex joint_id, std::shared_ptr<monopod_drivers::EncoderInterface> encoder, const double &gear_ratio, const double &zero_angle, const bool &reverse_polarity = false)

Construct a new EncoderJointModule object.

Parameters
  • encoder – is the C++ object allowing us to receive sensor data.

  • gear_ratio – is the gear ratio between the encoder and the joint.

  • zero_angle – is the angle between the closest positive encoder index and the zero configuration.

  • reverse_polarity

virtual void set_zero_angle(const double &zero_angle)

Set the zero_angle. The zero_angle is the angle between the closest positive encoder index and the zero configuration.

Parameters

zero_angle – (rad)

virtual void set_joint_polarity(const bool &reverse_polarity)

Define if the encoder should turn clock-wize or counter clock-wize.

Parameters

reverse_polarity – true:reverse rotation axis, false:do nothing.

virtual double get_measured_angle() const

Get the measured angle of the joint.

Returns

double (rad).

virtual double get_measured_velocity() const

Get the measured velocity of the joint. This data is computed on board of the control card.

Returns

double (rad/s).

virtual double get_measured_acceleration() const

Get the measured acceleration of the joint. This data is computed on board of the control card.

Returns

double (rad/s^2).

virtual double get_measured_index_angle() const

Get the measured index angle. There is one index per encoder rotation so there are gear_ratio indexes per joint rotation.

Returns

double (rad).

virtual double get_zero_angle() const

Get the zero_angle_. These are the angle between the starting pose and the theoretical zero pose.

Returns

double (rad).

virtual void set_limit(const Measurements &index, const JointLimit &limit)

Set the limit of the provided meassurement index.

Parameters
  • index – of the position type to set limit of

  • limit – is a struct holding the limit for the specified meassurement.

virtual JointLimit get_limit(const Measurements &index) const

Get the limit of the provided meassurement index.

Parameters

index – of the position type to set limit of

virtual bool check_limits() const

Check all of the joint limits. True if in range otherwise false.

virtual void print() const

Print the motor status and state.

struct HomingState
#include <motor_joint_module.hpp>

State variables required for the homing.

Public Members

int joint_id = 0

Id of the joint. Just used for debug prints.

double search_distance_limit_rad = 0.0

Max. distance to move while searching the encoder index.

double home_offset_rad = 0.0

Offset from home position to zero position.

double profile_step_size_rad = 0.0

Step size for the position profile.

long int last_encoder_index_time_index = 0

Timestamp from when the encoder index was seen the last time.

uint32_t step_count = 0

Number of profile steps already taken.

double target_position_rad = 0.0

Current target position of the position profile.

HomingReturnCode status = HomingReturnCode::NOT_INITIALIZED

Current status of the homing procedure.

double start_position

Position at which homing is started.

double end_position

Position at which homing is ended (before resetting position).

This is only set when status is SUCCEEDED. Together with start_position it can be used to determine the distance the joint travelled during the homing procedure (e.g. useful for home offset calibration).

struct JointLimit
#include <common_header.hpp>

Structure holding joint limits.

class Leg
#include <leg.hpp>

The leg class is the implementation of the LegInterface. This is the decalartion and the definition of the class as it is very simple.

Public Functions

inline Leg(const std::shared_ptr<MotorJointModule> &hip_joint_module, const std::shared_ptr<MotorJointModule> &knee_joint_module)

Enumerate the num_joints For readability.

Construct the LegInterface object

inline ~Leg()

Destroy the LegInterface object.

inline bool calibrate(const double &hip_home_offset_rad, const double &knee_home_offset_rad)

Calibrate the leg. See motor_joint_module.hpp for explanation of parameters and logic.

inline bool goto_position(const double &hip_home_position = 0, const double &knee_home_position = 0)

Allow the robot to go to a desired pose. Once the control done 0 torques is sent. By default this function will home.

Parameters
  • hip_home_position – (rad) Final desired hip position

  • knee_home_position – (rad) Final desired knee position

Returns

true if successfully went to location otherwise false.

inline void start_holding_loop()

Start loop to hold robot at current leg position. Current position is defined as the position meassured when the function was called.

inline bool is_hold_current_pos()

True if currrently holding at some position, otherwise false.

inline void stop_hold_current_pos()

Stops any hold loop currently running.

class Monopod
#include <monopod.hpp>

Drivers for open sim2real monopod. Interfaces with the monopod TI motors using monopod_drivers::BlmcJointModule. This class creates a real time control thread which reads and writes from a buffer exposed to the public api.

Public Functions

Monopod()

Construct a new Monopod object.

~Monopod()

Destroy the Monopod object.

bool initialize(Mode monopod_mode, bool dummy_mode = false)

Initialize can_bus connections to encoder board and motor board.

Parameters

monopod_mode – defines the task mode of the monopod. Can also specify individual boards.

bool initialized() const

is the monopod sdk Initialized?.

void print(const Vector<int> &joint_indexes = {}) const

Print the motor status and state.

void start_safety_loop()

This method is a helper to start the thread safety_loop. Requires the class to be initialized before the safety_loop can be started.

void goto_position(const double &hip_home_position = 0, const double &knee_home_position = 0)

This method is a helper class to goto some position for the leg. This requires the board to be initialized in any mode which has active motors. Additionally this function will pause the limit checks and will reset the board before executing the position control. This is to allow homing from outside the limits.

void hold_position()

This method is a helper class to hold the position the leg was in when the function was called. This function will only change the state if the motor board is active. otherwise nothing will happen. When holding the monopod wll be a read only state until the holding is killed.

bool is_hold_position()

Is the monopod holding the current leg position?

void stop_hold_position()

Stops robot from holding.

void calibrate(const double &hip_home_offset_rad = 0, const double &knee_home_offset_rad = 0)

Calibrate the Encoders.

Parameters
  • hip_home_offset_rad – hip offset from found encoder index 0 (rad)

  • knee_home_offset_rad – knee offset from found encoder index 0 (rad)

std::string get_model_name() const

Get model name.

Returns

String of model name

std::unordered_map<std::string, int> get_joint_names() const

Get a map of ‘active’ joint strings indexing their enumerator index.

Returns

Unordered map of joint name strings as key and index as value

bool is_joint_controllable(const int joint_index)

check if the joint is a controllable joint (has a motor) or only a observation joint (encoder only).

Parameters

joint_index – name of the joint we want to access

Returns

bool whether joint is controllable

bool valid()

Is the robot in a valid state? HOLDING state and safemode is considered invalid.

Returns

bool, true if valid otherwise false.

void reset(const bool &move_to_zero = true)

If the joint module is not valid (safemode after limit reached) the joint will be reset into a valid state (The joint must be set back into the valid state first otherwise it will trigger the limits again). Additionally by default the reset function will attempt to control the robot leg to ther zero pose. Regardless of status of the zero pose movement the robot reset will pause the motors to avoid a timeout.

Parameters

move_to_zero – True if you want the monopod to move into zero position, otherwise false.

bool set_torque_target(const double &torque_target, const int joint_index)

Set the torque target for some joint index. Return a bool whether successful.

Parameters
  • torque_target – is the desired torque target for indexed joint

  • joint_index – name of the joint we want to access

Returns

bool whether setting the value was successfull

bool set_torque_targets(const Vector<double> &torque_targets, const Vector<int> &joint_indexes = {})

Set the torque targets for all joint indexes. Return a bool whether successful.

Warning

Note: if it fails the behaviour is undefined. For example if first 3 joints are right but one bad index it will updatethe good ones the fail on the bad one.

Parameters
  • torque_targets – vector of desired torque targets for indexed joints

  • joint_indexes – names of the joints we want to access

Returns

bool whether setting the value was successfull

bool set_pid(const int &p, const int &i, const int &d, const int &joint_index)

Set the PID parameters of the joint.

Parameters

pid – The desired PID parameters.

Returns

True for success, false otherwise.

bool set_joint_position_limit(const double &max, const double &min, const int &joint_index)

Set the maximum Position of the joint.

This limit when reached will kill the robot for safety

Parameters
  • max – A double with the maximum position of the joint.

  • min – A double with the minimum position of the joint.

  • joint_index – name of the joint we want to access

Returns

True for success, false otherwise.

bool set_joint_velocity_limit(const double &max, const double &min, const int &joint_index)

Set the maximum velocity of the joint.

This limit when reached will kill the robot for safety

Parameters
  • max – A double with the maximum velocity of the joint.

  • min – A double with the minimum velocity of the joint.

  • joint_index – name of the joint we want to access

Returns

True for success, false otherwise.

bool set_joint_acceleration_limit(const double &max, const double &min, const int &joint_index)

Set the maximum acceleration of the joint.

This limit when reached will kill the robot for safety

Parameters
  • max – A double with the maximum acceleration of the joint.

  • min – A double with the minimum acceleration of the joint.

  • joint_index – name of the joint we want to access

Returns

True for success, false otherwise.

bool set_max_torque_target(const double &max_torque_target, const int &joint_index)

Set the maximum torque target of the joint.

This limit when reached will kill the robot for safety

Parameters
  • max_torque_target – A double with the maximum torque of the joint.

  • joint_index – name of the joint we want to access

Returns

True for success, false otherwise.

std::optional<PID> get_pid(const int &joint_index) const

Get the PID parameters of the joint.

If no PID parameters have been set, the default parameters are returned.

Returns

The joint PID parameters.

std::optional<JointLimit> get_joint_position_limit(const int &joint_index) const

Get the position limits of the joint.

Returns

The position limits of the joint.

std::optional<JointLimit> get_joint_velocity_limit(const int &joint_index) const

Get the velocity limits of the joint.

Returns

The velocity limits of the joint.

std::optional<JointLimit> get_joint_acceleration_limit(const int &joint_index) const

Get the velocity limits of the joint.

Returns

The velocity limits of the joint.

std::optional<double> get_max_torque_target(const int &joint_index) const

Get the max torque.

Parameters

joint_index

Returns

std::optional<double> containing the max torque if success

std::optional<double> get_torque_target(const int &joint_index) const

Get the torque.

Parameters

joint_index

Returns

std::optional<double> containing the torque if success

std::optional<Vector<double>> get_torque_targets(const Vector<int> &joint_indexes = {}) const

Get the torques of indexed joints.

Parameters

joint_index

Returns

std::optional<double> containing the torque if success

std::optional<double> get_position(const int &joint_index) const

Get the position of joint.

Parameters

joint_index – name of the joint we want to access

Returns

std::optional<double> containing the position if success value of the position (NULL if not valid)

std::optional<double> get_velocity(const int &joint_index) const

Get the velocity of the joint.

Parameters

joint_index – name of the joint we want to access

Returns

std::optional<double> containing the velocity if success

std::optional<double> get_acceleration(const int &joint_index) const

Get the acceleration of the joint.

Parameters

joint_index – name of the joint we want to access

Returns

std::optional<double> containing the acceleration if success

std::optional<Vector<double>> get_positions(const Vector<int> &joint_indexes = {}) const

Get the position of the joint indexes.

Parameters

joint_indexes – names of the joints we want to access

Returns

std::optional<vector<double>> containing vector of positions if success

std::optional<Vector<double>> get_velocities(const Vector<int> &joint_indexes = {}) const

Get the velocity of the joint indexes.

Parameters

joint_indexes – names of the joints we want to access

Returns

std::optional<Vector<double>> containing vector of velocities if success

std::optional<Vector<double>> get_accelerations(const Vector<int> &joint_indexes = {}) const

Get the acceleration of the joint indexes.

Parameters

joint_indexes – names of the joints we want to access

Returns

std::optional<Vector<double>> containing vector of accelerations if success

Public Members

const std::unordered_map<std::string, int> joint_names = {{"hip_joint", hip_joint}, {"knee_joint", knee_joint}, {"boom_connector_joint", boom_connector_joint}, {"planarizer_yaw_joint", planarizer_yaw_joint}, {"planarizer_pitch_joint", planarizer_pitch_joint}}

Joint names indexed same as enumerator.

class Motor : public monopod_drivers::MotorInterface, public monopod_drivers::Encoder
#include <motor.hpp>

This class implements the MotorInterface.

Public Functions

Motor(Ptr<ControlBoardsInterface> board, JointNamesIndex motor_id)

Construct a new Motor object.

Parameters
  • board – is the ControlBoards to be used.

  • motor_id – is the id of the motor on the on-board card

inline virtual ~Motor()

Destroy the Motor object.

inline virtual void send_if_input_changed()

Actually send the command and controls via the network, See MotorInterface for more information.

virtual Ptr<const ScalarTimeseries> get_measurement(const Measurements &index) const

Get the measurements.

Getters

Parameters

index

Returns

Ptr<const ScalarTimeseries> the pointer to the desired measurement history.

virtual Ptr<const StatusTimeseries> get_status() const

Get the status.

Parameters

index

Returns

Ptr<const StatusTimeseries> the pointer to the desired status history.

virtual Ptr<const ScalarTimeseries> get_current_target() const

Get the current target to be sent.

Returns

Ptr<const ScalarTimeseries> the list of current values to be sent.

virtual Ptr<const ScalarTimeseries> get_sent_current_target() const

Get the already sent current target values.

Returns

Ptr<const ScalarTimeseries>

virtual void set_current_target(const double &current_target)

Set the current (Ampere) target. See MotorInterface for more information.

Setters

Parameters

current_target – in Ampere

inline virtual void set_command(const ControlBoardsCommand &command)

Set the command. See MotorInterface for more information.

Parameters

command

virtual void print() const

Print the motor status and state.

class MotorInterface : public monopod_drivers::EncoderInterface
#include <motor.hpp>

This class declares an interface to the motor. It allows the user to access the sensors data as well as sending controls. The only control supported for now is the current.

Subclassed by monopod_drivers::Motor

Public Functions

inline virtual ~MotorInterface()

Destroy the MotorInterface object.

virtual void send_if_input_changed() = 0

Actually send the commands and controls.

virtual Ptr<const ScalarTimeseries> get_current_target() const = 0

Get the current target object.

Getters

Returns

Ptr<const ScalarTimeseries> the list of the current values to be sent.

virtual Ptr<const ScalarTimeseries> get_sent_current_target() const = 0

Get the history of the sent current targets.

Returns

Ptr<const ScalarTimeseries>

virtual void set_current_target(const double &current_target) = 0

Set the current target. This function saves the data internally. Please call send_if_input_changed() to actually send the data.

Setters

Parameters

current_target

virtual void set_command(const ControlBoardsCommand &command) = 0

Set the command. Save internally a command to be apply by the motor board. This function save the command internally. Please call send_if_input_changed() to actually send the data.

Parameters

command

class MotorJointModule : public monopod_drivers::EncoderJointModule
#include <motor_joint_module.hpp>

The MotorJointModule class is containing the joint information. It is here to help converting the data from the motor side to the joint side. It also allows the calibration of the joint position during initialization.

Public Functions

MotorJointModule(JointNamesIndex joint_id, std::shared_ptr<monopod_drivers::MotorInterface> motor, const double &motor_constant, const double &gear_ratio, const double &zero_angle, const bool &reverse_polarity = false)

Construct a new MotorJointModule object.

Parameters
  • motor – is the C++ object allowing us to send commands and receive sensor data.

  • motor_constant – ( \( k \)) is the torque constant of the motor \( \tau_{motor} = k * i_{motor} \)

  • gear_ratio – is the gear ratio between the motor and the joint.

  • zero_angle – is the angle between the closest positive motor index and the zero configuration.

  • reverse_polarity

  • max_current

virtual void set_torque(const double &desired_torque)

Set the joint torque to be sent.

Parameters

desired_torque – (Nm)

virtual void send_torque()

send the joint torque to the motor. The conversion between joint torque and motor current is done automatically.

virtual void set_max_torque(const double &max_torque)

Set the maximum admissible joint torque that can be applied.

Returns

double

virtual double get_max_torque() const

Get the maximum admissible joint torque that can be applied.

Returns

double

virtual double get_sent_torque() const

Get the sent joint torque.

Returns

double (Nm).

virtual double get_measured_torque() const

Get the measured joint torque.

Returns

double (Nm).

void set_position_control_gains(double kp, double kd)

Set control gains for PD position controller.

Parameters
  • kp – P gain ( (Nm) / rad ).

  • kd – D gain ( (Nm) / (rad/s) ).

double execute_position_controller(double target_position_rad) const

Execute one iteration of the position controller.

Parameters

target_position_rad – Target position (rad).

Returns

Torque command (Nm).

void homing_at_current_position(double home_offset_rad)

Set zero position relative to current position.

Parameters

home_offset_rad – Offset from home position to zero position. Unit: radian.

void init_homing(double search_distance_limit_rad, double home_offset_rad, double profile_step_size_rad = 0.001)

Initialize the homing procedure.

This has to be called before update_homing().

Parameters
  • search_distance_limit_rad – Maximum distance the motor moves while searching for the encoder index. Unit: radian.

  • home_offset_rad – Offset from home position to zero position. Unit: radian.

  • profile_step_size_rad – Distance by which the target position of the position profile is changed in each step. Set to a negative value to search for the next encoder index in negative direction. Unit: radian.

HomingReturnCode update_homing()

Perform one step of homing on encoder index.

Searches for the next encoder index in positive direction and, when found, sets it as home position.

Only performs one step, so this method needs to be called in a loop. This method only set the control, one MUST send the control for the motor after calling this method.

The motor is moved with a position profile until either the encoder index is reached or the search distance limit is exceeded. The position is controlled with a simple PD controller.

If the encoder index is found, its position is used as home position. The zero position is offset from the home position by adding the “home

offset” to it (i.e. zero = home pos. + home offset). If the search distance limit is reached before the encoder index occurs, the homing fails.

Returns

Status of the homing procedure.

double get_distance_travelled_during_homing() const

Get distance between start and end position of homing.

Compute the distance that the joint moved between initialization of homing and reaching the home position.

This can be used to determine the home offset by first moving the joint to the desired zero position, then executing the homing and finally calling this function which will provide the desired home offset.

Returns

Distance between start and end position of homing.

struct PID
#include <common_header.hpp>

Structure holding the PID values for the joint.

template<int ORDER>
class Polynome
#include <polynome.hpp>

Simple class that defines \( P(x) \) a polynome of order ORDER. It provide simple methods to compute \( P(x) \), \( \frac{dP}{dx}(x) \), and \( \frac{dP^2}{dx^2}(x) \).

tparam ORDER

is the order of the polynome

Subclassed by monopod_drivers::TimePolynome< ORDER >

Public Functions

Polynome()

Constructor

~Polynome()

Destructor

double compute(double x)

Compute the value.

double compute_derivative(double x)

Compute the value of the derivative.

double compute_sec_derivative(double x)

Compute the value of the second derivative.

void get_coefficients(Coefficients &coefficients) const

Get the coefficients.

void set_coefficients(const Coefficients &coefficients)

Set the coefficients.

void print() const

Print the coefficient.

template<int ORDER>
class TimePolynome : public monopod_drivers::Polynome<ORDER>
#include <polynome.hpp>

Simple class that defines \( P(t) \) a polynome of order ORDER. With \( t \) being the time in any units. It provide simple methods to compute safely \( P(time) \), \( \frac{dP}{dt}(t) \), and \( \frac{dP^2}{dt^2}(t) \).

tparam ORDER

Public Functions

inline TimePolynome()

Constructor

inline ~TimePolynome()

Destructor

double compute(double t)

Compute the value.

double compute_derivative(double t)

Compute the value of the derivative.

double compute_sec_derivative(double t)

Compute the value of the second derivative.

void set_parameters(double final_time, double init_pose, double init_speed, double final_pose)

Computes a polynome trajectory according to the following constraints:

\[\begin{split}\begin{eqnarray*} P(0) &=& init_pose \\ P(0) &=& init_speed = 0 \\ P(0) &=& init_acc = 0 \\ P(final_time_) &=& final_pose \\ P(final_time_) &=& final_speed = 0 \\ P(final_time_) &=& final_acc = 0 \end{eqnarray*}\end{split}\]

Parameters
  • final_time – is used in the constraints.

  • init_pose – is used in the constraints.

  • init_speed – is used in the constraints.

  • final_pose – is used in the constraints.