vulp  2.3.0
vulp::actuation::Interface Class Referenceabstract

Base class for actuation interfaces. More...

#include <Interface.h>

Public Member Functions

 Interface (const ServoLayout &servo_layout)
 Initialize actuation interface for a given servo layout. More...
 
virtual ~Interface ()=default
 Virtual destructor so that derived destructors are called properly. More...
 
virtual void cycle (const moteus::Data &data, std::function< void(const moteus::Output &)> callback)=0
 Spin a new communication cycle. More...
 
virtual void reset (const Dictionary &config)=0
 Reset interface using a new servo layout. More...
 
virtual void observe (Dictionary &observation) const =0
 Write servo and IMU observations to dictionary. More...
 
const ServoLayoutservo_layout () const noexcept
 Get servo layout. More...
 
const std::map< int, int > & servo_bus_map () const noexcept
 Map from servo ID to the CAN bus the servo is connected to. More...
 
const std::map< int, std::string > & servo_joint_map () const noexcept
 Map from servo ID to joint name. More...
 
std::vector< moteus::ServoCommand > & commands ()
 Get servo commands. More...
 
const std::vector< moteus::ServoReply > & replies () const
 Get servo replies. More...
 
moteus::Data & data ()
 Get joint command-reply data. More...
 
void initialize_action (Dictionary &action)
 Initialize action dictionary with keys corresponding to the servo layout. More...
 
void write_position_commands (const Dictionary &action)
 Write position commands from an action dictionary. More...
 
void write_stop_commands () noexcept
 Stop all servos. More...
 

Detailed Description

Base class for actuation interfaces.

Definition at line 24 of file Interface.h.

Constructor & Destructor Documentation

◆ Interface()

vulp::actuation::Interface::Interface ( const ServoLayout servo_layout)
inlineexplicit

Initialize actuation interface for a given servo layout.

Parameters
[in]servo_layoutServo layout.

Definition at line 30 of file Interface.h.

◆ ~Interface()

virtual vulp::actuation::Interface::~Interface ( )
virtualdefault

Virtual destructor so that derived destructors are called properly.

Member Function Documentation

◆ commands()

std::vector<moteus::ServoCommand>& vulp::actuation::Interface::commands ( )
inline

Get servo commands.

Definition at line 87 of file Interface.h.

◆ cycle()

virtual void vulp::actuation::Interface::cycle ( const moteus::Data &  data,
std::function< void(const moteus::Output &)>  callback 
)
pure virtual

Spin a new communication cycle.

Parameters
[in,out]dataBuffer to read commands from and write replies to.
callbackFunction to call when the cycle is over.

The callback will be invoked from an arbitrary thread when the communication cycle has completed. All memory pointed to by data must remain valid until the callback is invoked.

Implemented in vulp::actuation::Pi3HatInterface, vulp::actuation::MockInterface, and vulp::actuation::BulletInterface.

◆ data()

moteus::Data& vulp::actuation::Interface::data ( )
inline

Get joint command-reply data.

This field is meant to become internal when we refactor spine servo observations into actuation interfaces.

Definition at line 97 of file Interface.h.

◆ initialize_action()

void vulp::actuation::Interface::initialize_action ( Dictionary &  action)

Initialize action dictionary with keys corresponding to the servo layout.

Parameters
[out]actionAction dictionary.

Definition at line 27 of file Interface.cpp.

◆ observe()

virtual void vulp::actuation::Interface::observe ( Dictionary &  observation) const
pure virtual

Write servo and IMU observations to dictionary.

Parameters
[out]observationDictionary to write ot.

Implemented in vulp::actuation::Pi3HatInterface, vulp::actuation::MockInterface, and vulp::actuation::BulletInterface.

◆ replies()

const std::vector<moteus::ServoReply>& vulp::actuation::Interface::replies ( ) const
inline

Get servo replies.

Definition at line 90 of file Interface.h.

◆ reset()

virtual void vulp::actuation::Interface::reset ( const Dictionary &  config)
pure virtual

Reset interface using a new servo layout.

Parameters
[in]configAdditional configuration dictionary.

Implemented in vulp::actuation::Pi3HatInterface, vulp::actuation::MockInterface, and vulp::actuation::BulletInterface.

◆ servo_bus_map()

const std::map<int, int>& vulp::actuation::Interface::servo_bus_map ( ) const
inlinenoexcept

Map from servo ID to the CAN bus the servo is connected to.

Definition at line 77 of file Interface.h.

◆ servo_joint_map()

const std::map<int, std::string>& vulp::actuation::Interface::servo_joint_map ( ) const
inlinenoexcept

Map from servo ID to joint name.

Definition at line 82 of file Interface.h.

◆ servo_layout()

const ServoLayout& vulp::actuation::Interface::servo_layout ( ) const
inlinenoexcept

Get servo layout.

Definition at line 74 of file Interface.h.

◆ write_position_commands()

void vulp::actuation::Interface::write_position_commands ( const Dictionary &  action)

Write position commands from an action dictionary.

Parameters
[in]actionAction to read commands from.

Definition at line 40 of file Interface.cpp.

◆ write_stop_commands()

void vulp::actuation::Interface::write_stop_commands ( )
inlinenoexcept

Stop all servos.

Parameters
[out]commandsServo commands to set to stop.

This function does not and should not throw, as it will be called by default if any exception is caught from the spine control loop.

Definition at line 118 of file Interface.h.


The documentation for this class was generated from the following files: