vulp
2.3.0
|
Interface to moteus controllers. More...
#include <Pi3HatInterface.h>
Public Member Functions | |
Pi3HatInterface (const ServoLayout &layout, const int can_cpu, const Pi3Hat::Configuration &pi3hat_config) | |
Configure interface and spawn CAN thread. More... | |
~Pi3HatInterface () | |
Stop CAN thread. More... | |
void | reset (const Dictionary &config) override |
Reset interface. More... | |
void | observe (Dictionary &observation) const override |
Write actuation-interface observations to dictionary. More... | |
void | cycle (const moteus::Data &data, std::function< void(const moteus::Output &)> callback) final |
Spin a new communication cycle. More... | |
Public Member Functions inherited from vulp::actuation::Interface | |
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... | |
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... | |
Interface to moteus controllers.
Internally it uses a background thread to operate the pi3hat, enabling the main thread to perform work while servo communication is taking place.
Definition at line 43 of file Pi3HatInterface.h.
vulp::actuation::Pi3HatInterface::Pi3HatInterface | ( | const ServoLayout & | layout, |
const int | can_cpu, | ||
const Pi3Hat::Configuration & | pi3hat_config | ||
) |
Configure interface and spawn CAN thread.
[in] | layout | Servo layout. |
[in] | can_cpu | CPUID of the core to run the CAN thread on. |
[in] | pi3hat_config | Configuration for the pi3hat. |
Definition at line 15 of file Pi3HatInterface.cpp.
vulp::actuation::Pi3HatInterface::~Pi3HatInterface | ( | ) |
Stop CAN thread.
Definition at line 22 of file Pi3HatInterface.cpp.
|
finalvirtual |
Spin a new communication cycle.
[in] | data | Buffer to read commands from and write replies to. |
[in] | 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.
Implements vulp::actuation::Interface.
Definition at line 54 of file Pi3HatInterface.cpp.
|
overridevirtual |
Write actuation-interface observations to dictionary.
[out] | observation | Dictionary to write ot. |
Implements vulp::actuation::Interface.
Definition at line 40 of file Pi3HatInterface.cpp.
|
overridevirtual |
Reset interface.
[in] | config | Additional configuration dictionary. |
Implements vulp::actuation::Interface.
Definition at line 38 of file Pi3HatInterface.cpp.