vulp
2.3.0
|
#include <MockInterface.h>
Public Member Functions | |
MockInterface (const ServoLayout &layout, const double dt) | |
Create mock actuator interface. More... | |
~MockInterface ()=default | |
Default destructor. 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 |
Simulate 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... | |
Definition at line 20 of file MockInterface.h.
vulp::actuation::MockInterface::MockInterface | ( | const ServoLayout & | layout, |
const double | dt | ||
) |
Create mock actuator interface.
[in] | params | Interface parameters. |
Definition at line 11 of file MockInterface.cpp.
|
default |
Default destructor.
|
finalvirtual |
Simulate a new communication cycle.
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.
Implements vulp::actuation::Interface.
Definition at line 39 of file MockInterface.cpp.
|
overridevirtual |
Write actuation-interface observations to dictionary.
[out] | observation | Dictionary to write ot. |
Implements vulp::actuation::Interface.
Definition at line 29 of file MockInterface.cpp.
|
overridevirtual |
Reset interface.
[in] | config | Additional configuration dictionary. |
Implements vulp::actuation::Interface.
Definition at line 27 of file MockInterface.cpp.