Skip to content

Commit f87f2a4

Browse files
Refactor YarpRobotLoggerDevice to use record() and stopRecording() RPC commands
- Replaced startLogging() with record() in YarpRobotLoggerDevice class. - Introduced stopRecording() method to handle stopping the recording without saving data. - Updated the internal state management to track if recording is prepared. - Modified the logging behavior to reflect the new recording commands. - Adjusted the test cases to validate the new RPC commands and their functionality. - Added new XML configuration files for testing without auto-start logging.
1 parent c2d0a5c commit f87f2a4

File tree

9 files changed

+623
-243
lines changed

9 files changed

+623
-243
lines changed

README.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,13 @@ cmake --build . --config Release --target install
101101
# :computer: Some utilities
102102
The **bipedal-locomotion-framework** ships also some utilities that can help you in the everyday tests on a real robot. You can find them in the [`utilities` folder](./utilities). Each utility contains a well-documented` README` where you can find further details.
103103

104+
# :robot: Devices
105+
The **bipedal-locomotion-framework** also provides YARP devices in the [`devices` folder](./devices).
106+
107+
| Device | Description |
108+
| :--------------------------------------------: | :----------------------------------------------------------: |
109+
| [`YarpRobotLoggerDevice`](./devices/YarpRobotLoggerDevice) | Logs robot sensor/actuator data, cameras, and exogenous signals to `.mat` files. Controllable via RPC (`record`, `saveData`, `stopRecording`). |
110+
104111
# :snake: Python
105112
**bipedal-locomotion-framework** also provides Python bindings. Only a small set of the components implemented in the library have the corresponding Python bindings.
106113

Lines changed: 122 additions & 112 deletions
Original file line numberDiff line numberDiff line change
@@ -1,140 +1,150 @@
11
# YARPRobotLoggerDevice
22

3-
The **YARPRobotLoggerDevice** is a YARP device based on `YarpSensorBridge` and [`robometry`](https://github.com/robotology/robometry) that allows logging data from robot sensors and actuators in a mat file.
3+
The **YARPRobotLoggerDevice** is a YARP device based on `YarpSensorBridge` and [`robometry`](https://github.com/robotology/robometry) that logs data from robot sensors and actuators into `.mat` files. It also supports logging cameras (as `.mp4` videos or image frames), exogenous signals streamed over YARP ports, text logs, and frame transforms.
44

5-
## Configuration Parameters
6-
The logger is currently supported only for the robots listed in the [application folder](./app/robots). Each robot folder contains:
5+
## Quick start
76

8-
- `launch-yarp-robot-logger.xml`: Configuration parameters for the `yarprobotinterface` to launch the logger device and associated devices.
9-
- `yarp-robot-logger.xml`: Configuration parameters for the logger device.
10-
- `blf-yarp-robot-logger-interfaces`: Folder containing all interfaces used by the logger device to log data.
11-
12-
## How to Use the Logger
13-
To use the logger, launch the `yarprobotinterface` with the `launch-yarp-robot-logger.xml` configuration file:
7+
Launch the logger with `yarprobotinterface`:
148

159
```console
1610
yarprobotinterface --config launch-yarp-robot-logger.xml
1711
```
18-
When you close the yarprobotinterface, the logger will save the logged data in a mat file. Additionally, a md file will contain information about the software version in the robot setup. If video recording is enabled, a mp4 file with the video recording will also be generated. All these files will be saved in the working directory in which `yarprobotinterface` has been launched.
19-
20-
## How to log exogenous data
21-
The `YarpRobotLoggerDevice` can also log exogenous data, i.e., data not directly provided by the robot sensors and actuators. To do this:
22-
1. modify the `yarp-robot-logger.xml` file to specify the exogenous data to log
23-
2. modify the application that streams the exogenous data
24-
25-
### Modification `yarp-robot-logger.xml` configuration file
26-
Modify the [`ExogenousSignalGroup` in the `yarp-robot-logger.xml` file](https://github.com/ami-iit/bipedal-locomotion-framework/blob/a3a8e9cb8a0c3532db81d814d4851009f8134195/devices/YarpRobotLoggerDevice/app/robots/ergoCubSN000/yarp-robot-logger.xml#L27-L37) to log the data streamed by an application that allows the robot to balance:
27-
```xml
28-
<group name="ExogenousSignals">
29-
<!-- List containing the names of exogenous signals. Each name should be associated to a sub-group -->
30-
<param name="vectors_collection_exogenous_inputs">("balancing")</param>
31-
<param name="vectors_exogenous_inputs">()</param>
32-
33-
<!-- Sub-group containing the information about the exogenous signal "balancing" -->
34-
<group name="balancing">
35-
<!-- Name of the port opened by the logger used to retrieve the exogenous signal data -->
36-
<param name="local">"/yarp-robot-logger/exogenous_signals/balancing"</param>
37-
38-
<!-- Name of the port opened by the application used to stream the exogenous signal data -->
39-
<param name="remote">"/balancing-controller/logger"</param>
40-
41-
<!-- Name of the exogenous signal (this will be the name of the matlab struct containing all the data associated to the exogenous signal) -->
42-
<param name="signal_name">"balancing"</param>
43-
44-
<!-- Carrier used in the port connection -->
45-
<param name="carrier">"udp"</param>
46-
</group>
47-
</group>
48-
```
49-
50-
### Stream exogenous data
51-
You need to modify the application that streams the exogenous data to open a port with the name specified in the `remote` parameter of the `balancing` sub-group. For example, if you want to stream the data from the your `balancing` application you need to use `BipedalLocomotion::YarpUtilities::VectorsCollectionServer` class as follows
52-
#### C++
53-
If your application is written in C++ you can use the `BipedalLocomotion::YarpUtilities::VectorsCollectionServer` class as follows
54-
55-
```c++
56-
#include <BipedalLocomotion/YarpUtilities/VectorsCollectionServer.h>
5712

58-
class Module
59-
{
60-
BipedalLocomotion::YarpUtilities::VectorsCollectionServer m_vectorsCollectionServer; /**< Logger server. */
61-
public:
62-
// all the other functions you need
63-
}
64-
```
65-
The `m_vectorsCollectionServer` helps you to handle the data you want to send and to populate the metadata. To use this functionality, call `BipedalLocomotion::YarpUtilities::VectorsCollectionServer::populateMetadata` during the configuration phase. Once you have finished populating the metadata you should call `BipedalLocomotion::YarpUtilities::VectorsCollectionServer::finalizeMetadata`
66-
```c++
67-
//This code should go into the configuration phase
68-
auto loggerOption = std::make_shared<BipedalLocomotion::ParametersHandler::YarpImplementation>(rf);
69-
if (!m_vectorsCollectionServer.initialize(loggerOption->getGroup("LOGGER")))
70-
{
71-
log()->error("[BalancingController::configure] Unable to configure the server.");
72-
return false;
73-
}
74-
75-
m_vectorsCollectionServer.populateMetadata("dcm::position::measured", {"x", "y"});
76-
m_vectorsCollectionServer.populateMetadata("dcm::position::desired", {"x", "y"});
77-
78-
m_vectorsCollectionServer.finalizeMetadata(); // this should be called only once
13+
By default (`auto_start_logging: true`) the logger starts recording immediately. When you close `yarprobotinterface` (e.g. with `Ctrl+C`), the recorded data is **automatically saved** before the device shuts down. All output files (`.mat`, `.mp4`, `.md`) are written to the working directory.
14+
15+
## RPC commands
16+
17+
The logger exposes an RPC port at `<port_prefix>/commands/rpc:i` (default: `/yarp-robot-logger/commands/rpc:i`). You can control recording with the following commands using `yarp rpc`:
18+
19+
```console
20+
yarp rpc /yarp-robot-logger/commands/rpc:i
7921
```
80-
In the main loop, add the following code to prepare and populate the data:
8122

82-
```c++
83-
m_vectorsCollectionServer.prepareData(); // required to prepare the data to be sent
84-
m_vectorsCollectionServer.clearData(); // optional see the documentation
23+
| Command | Description |
24+
|---|---|
25+
| `record` | Start recording. Initializes sensor bridge, cameras, telemetry buffers and begins the periodic acquisition loop. |
26+
| `saveData` | Save the recorded data to a `.mat` file and **stop recording**. The device returns to idle mode. Accepts an optional `tag` string that is appended to the filename (e.g. `saveData "walking_test"`). |
27+
| `saveData "<tag>"` | Same as above, with the tag included in the output filename: `robot_logger_device_<tag>_<timestamp>.mat`. |
28+
| `stopRecording` | Stop recording **without saving**. All buffered data is discarded and the device returns to idle mode. |
29+
30+
After `saveData` or `stopRecording`, you can call `record` again to start a new recording session.
8531

86-
// DCM
87-
m_vectorsCollectionServer.populateData("dcm::position::measured", <signal>);
88-
m_vectorsCollectionServer.populateData("dcm::position::desired", <signal>);
32+
### Example session
8933

90-
m_vectorsCollectionServer.sendData();
34+
```console
35+
$ yarp rpc /yarp-robot-logger/commands/rpc:i
36+
>> record
37+
Response: [ok]
38+
# ... robot performs some task ...
39+
>> saveData "walking_trial_1"
40+
Response: [ok]
41+
# data saved to robot_logger_device_walking_trial_1_<timestamp>.mat
42+
# logger is now idle
43+
>> record
44+
Response: [ok]
45+
# ... another trial ...
46+
>> stopRecording
47+
Response: [ok]
48+
# data discarded, no file saved
9149
```
9250

93-
**Note:** Replace `<signal>` with the actual data you want to log.
51+
### Auto-start mode
9452

53+
When `auto_start_logging` is set to `true` (the default), `record` is called automatically at device startup. If set to `false`, the device starts in idle mode and waits for an explicit `record` RPC command.
9554

96-
#### Python
97-
If your application is written in Python you can use the `BipedalLocomotion.yarp_utilities.VectorsCollectionServer` class as follows
98-
```python
99-
import bipedal_locomotion_framework as blf
55+
## Configuration
56+
57+
The logger is currently supported for the robots listed in the [application folder](./app/robots). Each robot folder contains:
58+
59+
- `launch-yarp-robot-logger.xml`: `yarprobotinterface` configuration that launches the logger and associated devices.
60+
- `yarp-robot-logger.xml`: Logger device parameters.
61+
- `blf-yarp-robot-logger-interfaces/`: Interface configuration files for the sensor bridge.
62+
63+
### Key parameters
64+
65+
| Parameter | Default | Description |
66+
|---|---|---|
67+
| `sampling_period_in_s` | `0.01` | Logging period in seconds. |
68+
| `port_prefix` | `/yarp-robot-logger` | Prefix for all YARP ports opened by the logger. |
69+
| `auto_start_logging` | `true` | Start recording automatically on device startup. |
70+
| `log_robot_data` | `true` | Log joint states, motor states, FT sensors, IMUs, etc. |
71+
| `log_cameras` | `true` | Log camera images as video or frames. |
72+
| `log_text` | `true` | Log YARP text logging messages. |
73+
| `maximum_admissible_time_step` | - | Max time step between samples (skip logging on clock resets). |
74+
75+
## Logging exogenous data
10076

101-
class Module:
102-
def __init__(self):
103-
self.vectors_collection_server = blf.yarp_utilities.VectorsCollectionServer() # Logger server.
104-
# all the other functions you need
77+
The logger can also record exogenous data, i.e., signals not directly from robot sensors. To do this:
78+
79+
1. Configure the `ExogenousSignals` group in `yarp-robot-logger.xml`.
80+
2. Stream data from your application using `VectorsCollectionServer`.
81+
82+
### Configuration
83+
84+
Add an `ExogenousSignals` group to `yarp-robot-logger.xml`:
85+
86+
```xml
87+
<group name="ExogenousSignals">
88+
<param name="vectors_collection_exogenous_inputs">("balancing")</param>
89+
<param name="vectors_exogenous_inputs">()</param>
90+
91+
<group name="balancing">
92+
<param name="local">"/yarp-robot-logger/exogenous_signals/balancing"</param>
93+
<param name="remote">"/balancing-controller/logger"</param>
94+
<param name="signal_name">"balancing"</param>
95+
<param name="carrier">"udp"</param>
96+
</group>
97+
</group>
10598
```
106-
The `vectors_collection_server` helps you to handle the data you want to send and to populate the metadata. To use this functionality, call `BipedalLocomotion.yarp_utilities.VectorsCollectionServer.populate_metadata` during the configuration phase. Once you have finished populating the metadata you should call `BipedalLocomotion.yarp_utilities.VectorsCollectionServer.finalize_metadata`
107-
```python
108-
#This code should go into the configuration phase
109-
logger_option = blf.parameters_handler.StdParametersHandler()
110-
logger_option.set_parameter_string("remote", "/test/log")
111-
if not self.vectors_collection_server.initialize(logger_option):
112-
blf.log().error("[BalancingController::configure] Unable to configure the server.")
113-
raise RuntimeError("Unable to configure the server.")
114-
115-
# populate the metadata
116-
self.vectors_collection_server.populate_metadata("dcm::position::measured", ["x", "y"])
117-
self.vectors_collection_server.populate_metadata("dcm::position::desired", ["x", "y"])
118-
119-
self.vectors_collection_server.finalize_metadata() # this should be called only once when the metadata are ready
99+
100+
### Streaming from C++
101+
102+
```cpp
103+
#include <BipedalLocomotion/YarpUtilities/VectorsCollectionServer.h>
104+
105+
// Configuration phase
106+
BipedalLocomotion::YarpUtilities::VectorsCollectionServer server;
107+
server.initialize(loggerOption->getGroup("LOGGER"));
108+
server.populateMetadata("dcm::position::measured", {"x", "y"});
109+
server.populateMetadata("dcm::position::desired", {"x", "y"});
110+
server.finalizeMetadata();
111+
112+
// Main loop
113+
server.prepareData();
114+
server.clearData();
115+
server.populateData("dcm::position::measured", measuredSignal);
116+
server.populateData("dcm::position::desired", desiredSignal);
117+
server.sendData();
120118
```
121-
In the main loop, add the following code to prepare and populate the data:
119+
120+
### Streaming from Python
121+
122122
```python
123-
self.vectors_collection_server.prepare_data() # required to prepare the data to be sent
124-
self.vectors_collection_server.clear_data() # optional see the documentation
125-
self.vectors_collection_server.populate_data("dcm::position::measured", <signal>)
126-
self.vectors_collection_server.populate_data("dcm::position::desired", <signal>)
127-
self.vectors_collection_server.send_data()
123+
import bipedal_locomotion_framework as blf
124+
125+
# Configuration phase
126+
server = blf.yarp_utilities.VectorsCollectionServer()
127+
handler = blf.parameters_handler.StdParametersHandler()
128+
handler.set_parameter_string("remote", "/balancing-controller/logger")
129+
server.initialize(handler)
130+
server.populate_metadata("dcm::position::measured", ["x", "y"])
131+
server.populate_metadata("dcm::position::desired", ["x", "y"])
132+
server.finalize_metadata()
133+
134+
# Main loop
135+
server.prepare_data()
136+
server.clear_data()
137+
server.populate_data("dcm::position::measured", measured_signal)
138+
server.populate_data("dcm::position::desired", desired_signal)
139+
server.send_data()
128140
```
129-
**Note:** Replace `<signal>` with the actual data you want to log.
130141

131-
## How to visualize the logged data
132-
To visualize the logged data you can use [robot-log-visualizer](https://github.com/ami-iit/robot-log-visualizer). To use the `robot-log-visualizer` you can follow the instructions in the [README](https://github.com/ami-iit/robot-log-visualizer/blob/main/README.md) file.
142+
## Visualizing logged data
143+
144+
Use [robot-log-visualizer](https://github.com/ami-iit/robot-log-visualizer) to explore the `.mat` files:
133145

134-
Once you have installed the `robot-log-visualizer` you can open it from the command line with the following command:
135146
```console
136147
robot-log-visualizer
137148
```
138-
Then, you can open the mat file generated by the logger and explore the logged data as in the following video:
139149

140-
[robot-log-visualizer.webm](https://github.com/ami-iit/robot-log-visualizer/assets/16744101/3fd5c516-da17-4efa-b83b-392b5ce1383b)
150+
Then open the `.mat` file generated by the logger. See the [robot-log-visualizer README](https://github.com/ami-iit/robot-log-visualizer/blob/main/README.md) for details.

devices/YarpRobotLoggerDevice/include/BipedalLocomotion/YarpRobotLoggerDevice.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -226,6 +226,7 @@ class YarpRobotLoggerDevice : public yarp::dev::DeviceDriver,
226226
bool m_logFrames{false};
227227
bool m_logRobot{true};
228228
bool m_autoStartLogging{true};
229+
bool m_recordingPrepared{false};
229230
std::vector<std::string> m_textLoggingSubnames;
230231
std::vector<std::string> m_codeStatusCmds;
231232

@@ -263,8 +264,10 @@ class YarpRobotLoggerDevice : public yarp::dev::DeviceDriver,
263264
Eigen::Ref<gyro_t> gyro,
264265
Eigen::Ref<orientation_t> orientation);
265266

267+
virtual bool record() override;
266268
virtual bool saveData(const std::string& tag = "") override;
267-
virtual bool startLogging() override;
269+
virtual bool stopRecording() override;
270+
void stopRecordingThreads();
268271
bool setupRobotSensorBridge(std::weak_ptr<const ParametersHandler::IParametersHandler> params);
269272
bool setupRobotCameraBridge(std::weak_ptr<const ParametersHandler::IParametersHandler> params);
270273
bool setupTelemetry(std::weak_ptr<const ParametersHandler::IParametersHandler> params,

0 commit comments

Comments
 (0)