diff --git a/design_drafts/components_architecture_and_urdf_examples.md b/design_drafts/components_architecture_and_urdf_examples.md
index 734ff64..273a3be 100644
--- a/design_drafts/components_architecture_and_urdf_examples.md
+++ b/design_drafts/components_architecture_and_urdf_examples.md
@@ -108,7 +108,7 @@ Note:
* the communication is done using proprietary API to communicate with robot control box
* Data for all joints is exchanged in batch (at once)
* Multiple values can be commanded, e.g. goal position and the maximal velocity on the trajectory allowed
- * Examples: (humanoid robots?)
+ * Examples: humanoid robots (TALOS), 4 legged robot [solo](https://github.com/open-dynamic-robot-initiative/master-board/blob/master/documentation/BLMC_%C2%B5Driver_SPI_interface.md)
```xml
@@ -149,6 +149,7 @@ Note:
```
+
#### 3. Industrial Robots with integrated sensor
* the communication is done using proprietary API
* Data for all joints is exchanged in batch (at once)
@@ -401,3 +402,298 @@ Note:
```
+
+#### 10. Real robot examples
+
+##### [Solo: a 4 legged robot](https://github.com/open-dynamic-robot-initiative/master-board/blob/master/documentation/BLMC_%C2%B5Driver_SPI_interface.md)
+
+```xml
+
+
+ solo_control/SoloRobotHardware
+ 0.001
+ 0.001
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ contact_information
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ contact_information
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ contact_information
+ timestamp
+
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ timestamp
+
+
+
+ -1
+ 1
+
+
+ -1
+ 1
+
+
+ -0.5
+ 0.5
+
+ Kp
+ Kd
+ effort_limit
+ position
+ velocity
+ effort
+ coil_resistance
+ contact_information
+ timestamp
+
+
+
+ ros2_control_components/IMUSensor
+ orientation
+ velocity
+ acceleration
+ -54
+ 23
+ -10
+ 10
+
+
+
+```