vulp
2.3.0
|
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 ServoLayout & | servo_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... | |
Base class for actuation interfaces.
Definition at line 24 of file Interface.h.
|
inlineexplicit |
Initialize actuation interface for a given servo layout.
[in] | servo_layout | Servo layout. |
Definition at line 30 of file Interface.h.
|
virtualdefault |
Virtual destructor so that derived destructors are called properly.
|
inline |
Get servo commands.
Definition at line 87 of file Interface.h.
|
pure virtual |
Spin a new communication cycle.
[in,out] | data | Buffer to read commands from and write replies to. |
callback | Function 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.
|
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.
void vulp::actuation::Interface::initialize_action | ( | Dictionary & | action | ) |
Initialize action dictionary with keys corresponding to the servo layout.
[out] | action | Action dictionary. |
Definition at line 27 of file Interface.cpp.
|
pure virtual |
Write servo and IMU observations to dictionary.
[out] | observation | Dictionary to write ot. |
Implemented in vulp::actuation::Pi3HatInterface, vulp::actuation::MockInterface, and vulp::actuation::BulletInterface.
|
inline |
Get servo replies.
Definition at line 90 of file Interface.h.
|
pure virtual |
Reset interface using a new servo layout.
[in] | config | Additional configuration dictionary. |
Implemented in vulp::actuation::Pi3HatInterface, vulp::actuation::MockInterface, and vulp::actuation::BulletInterface.
|
inlinenoexcept |
Map from servo ID to the CAN bus the servo is connected to.
Definition at line 77 of file Interface.h.
|
inlinenoexcept |
Map from servo ID to joint name.
Definition at line 82 of file Interface.h.
|
inlinenoexcept |
Get servo layout.
Definition at line 74 of file Interface.h.
void vulp::actuation::Interface::write_position_commands | ( | const Dictionary & | action | ) |
Write position commands from an action dictionary.
[in] | action | Action to read commands from. |
Definition at line 40 of file Interface.cpp.
|
inlinenoexcept |
Stop all servos.
[out] | commands | Servo 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.