vulp  2.3.0
vulp.spine::Spine Class Reference

Loop transmitting actions to the actuation and observations to the agent. More...

#include <Spine.h>

Classes

struct  Parameters
 Spine parameters. More...
 

Public Member Functions

 Spine (const Parameters &params, actuation::Interface &interface, observation::ObserverPipeline &observers)
 Initialize spine. More...
 
void reset (const palimpsest::Dictionary &config)
 Reset the spine with a new configuration. More...
 
void run ()
 Run the spine loop until termination. More...
 
void cycle ()
 Spin one cycle of the spine loop. More...
 
void simulate (unsigned nb_substeps)
 Alternative to run where the actuation interface is cycled a fixed number of times, and communication cycles are not frequency-regulated. More...
 

Protected Attributes

const unsigned frequency_
 Frequency of the spine loop in [Hz]. More...
 
actuation::Interfaceactuation_
 Interface that communicates with actuators. More...
 
AgentInterface agent_interface_
 Shared memory mapping for inter-process communication. More...
 
std::future< actuation::moteus::Output > actuation_output_
 Future used to wait for moteus replies. More...
 
std::vector< actuation::moteus::ServoReply > latest_replies_
 Latest servo replies. They are copied and thread-safe. More...
 
palimpsest::Dictionary working_dict_
 All data from observation to action goes to this dictionary. More...
 
observation::ObserverPipeline observer_pipeline_
 Pipeline of observers, executed in that order. More...
 
mpacklog::Logger logger_
 Logger for the working_dict_ produced at each cycle. More...
 
std::vector< char > ipc_buffer_
 Buffer used to serialize/deserialize dictionaries in IPC. More...
 
const bool & caught_interrupt_
 Boolean flag that becomes true when an interruption is caught. More...
 
StateMachine state_machine_
 Internal state machine. More...
 
State state_cycle_beginning_
 State after the last Event::kCycleBeginning. More...
 
State state_cycle_end_
 State after the last Event::kCycleEnd. More...
 

Detailed Description

Loop transmitting actions to the actuation and observations to the agent.

The spine acts as the intermediary between the actuation interface (e.g. moteus servos connected to the CAN-FD bus) and an agent communicating over shared memory (the agent interface). It packs observations to the agent from actuation replies and commands to the actuation from agent actions.

The spine processes requests at the beginning and end of each control cycle according to its StateMachine. The overall specification of the state machine is summarized in the following diagram:

See StateMachine for more details.

Definition at line 45 of file Spine.h.

Constructor & Destructor Documentation

◆ Spine()

vulp.spine::Spine::Spine ( const Parameters params,
actuation::Interface interface,
observation::ObserverPipeline observers 
)

Initialize spine.

Parameters
[in]paramsSpine parameters.
[in,out]interfaceInterface to actuators.
[in,out]observersPipeline of observers to run, in that order, at each cycle.

Definition at line 24 of file Spine.cpp.

Member Function Documentation

◆ cycle()

void vulp.spine::Spine::cycle ( )

Spin one cycle of the spine loop.

Definition at line 96 of file Spine.cpp.

◆ reset()

void vulp.spine::Spine::reset ( const palimpsest::Dictionary &  config)

Reset the spine with a new configuration.

Parameters
[in]configNew global configuration dictionary, used to derive the servo layout (which servo is on which bus, corresponds to which joint) and forwarded to other components (e.g. observers).

Definition at line 58 of file Spine.cpp.

◆ run()

void vulp.spine::Spine::run ( )

Run the spine loop until termination.

Each iteration of the loop runs observers, computes the action and cycles the actuation interface. Additionally, this function collects debug values and logs everything.

Note
The spine will catch keyboard interrupts once this function is called.

Definition at line 80 of file Spine.cpp.

◆ simulate()

void vulp.spine::Spine::simulate ( unsigned  nb_substeps)

Alternative to run where the actuation interface is cycled a fixed number of times, and communication cycles are not frequency-regulated.

Parameters
[in]nb_substepsNumber of actuation cycles per action.

Thus function assumes the agent alternates acting and observing. Simulation steps are triggered at startup (to construct the initial observation) and at each action request.

Note
As its name suggests, do not use this function on a real robot.

Note that there is currently a delay of three substeps between observation and simulation. That is, the internal simulation state is always three substeps ahead compared to the values written to the observation dictionary in cycle_actuation. This decision is discussed in https://github.com/orgs/upkie/discussions/238#discussioncomment-8984290

Definition at line 102 of file Spine.cpp.

Member Data Documentation

◆ actuation_

actuation::Interface& vulp.spine::Spine::actuation_
protected

Interface that communicates with actuators.

The actuation interface communicates over the CAN-FD bus on real robots. Otherwise, it can be for instance a mock or a simulator interface.

Definition at line 146 of file Spine.h.

◆ actuation_output_

std::future<actuation::moteus::Output> vulp.spine::Spine::actuation_output_
protected

Future used to wait for moteus replies.

Definition at line 152 of file Spine.h.

◆ agent_interface_

AgentInterface vulp.spine::Spine::agent_interface_
protected

Shared memory mapping for inter-process communication.

Definition at line 149 of file Spine.h.

◆ caught_interrupt_

const bool& vulp.spine::Spine::caught_interrupt_
protected

Boolean flag that becomes true when an interruption is caught.

Definition at line 170 of file Spine.h.

◆ frequency_

const unsigned vulp.spine::Spine::frequency_
protected

Frequency of the spine loop in [Hz].

Definition at line 139 of file Spine.h.

◆ ipc_buffer_

std::vector<char> vulp.spine::Spine::ipc_buffer_
protected

Buffer used to serialize/deserialize dictionaries in IPC.

Definition at line 167 of file Spine.h.

◆ latest_replies_

std::vector<actuation::moteus::ServoReply> vulp.spine::Spine::latest_replies_
protected

Latest servo replies. They are copied and thread-safe.

Definition at line 155 of file Spine.h.

◆ logger_

mpacklog::Logger vulp.spine::Spine::logger_
protected

Logger for the working_dict_ produced at each cycle.

Definition at line 164 of file Spine.h.

◆ observer_pipeline_

observation::ObserverPipeline vulp.spine::Spine::observer_pipeline_
protected

Pipeline of observers, executed in that order.

Definition at line 161 of file Spine.h.

◆ state_cycle_beginning_

State vulp.spine::Spine::state_cycle_beginning_
protected

State after the last Event::kCycleBeginning.

Definition at line 176 of file Spine.h.

◆ state_cycle_end_

State vulp.spine::Spine::state_cycle_end_
protected

State after the last Event::kCycleEnd.

Definition at line 179 of file Spine.h.

◆ state_machine_

StateMachine vulp.spine::Spine::state_machine_
protected

Internal state machine.

Definition at line 173 of file Spine.h.

◆ working_dict_

palimpsest::Dictionary vulp.spine::Spine::working_dict_
protected

All data from observation to action goes to this dictionary.

Definition at line 158 of file Spine.h.


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