Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
298 changes: 297 additions & 1 deletion design_drafts/components_architecture_and_urdf_examples.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would propose to add this long example on the end of the file. Can you open a new subsection with a name "Real robot Examples" and than add yours. It would be also good to reference to this example 2.1.

The intention behind this is that user can fast scroll through all different examples and on the end have real-world use-cases to study them.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Any you can simply name the example "TALOS" as this is the name of the robot.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good to me. To be a bit more precise, TALOS and the 4 legged robot (SOLO) are two different robots. SOLO is mostly to highlight an original way to access the low level power electronics.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Then you are free to choose which one you think is more relevant and describe it


```xml
<ros2_control name="RRBotSystemMultiInterface" type="system">
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -401,3 +402,298 @@ Note:
</transmission>
</ros2_control>
```

#### 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
<ros2_control name="SOLO/12DOFLeggedSystemRobotMultiInterface" type="system">
<hardware>
<classType>solo_control/SoloRobotHardware</classType>
<param name="write_for_sec">0.001</param>
<param name="read_for_sec">0.001</param>
</hardware>
<joint name="front_left_leg_joint1">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="front_left_leg_joint2">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="front_left_leg_joint3">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>contact_information</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="front_right_leg_joint1">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="front_right_leg_joint2">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="front_right_leg_joint3">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>contact_information</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="hind_left_leg_joint1">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="hind_left_leg_joint2">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="hind_left_leg_joint3">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>contact_information</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>

<joint name="hind_right_leg_joint1">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="hind_right_leg_joint2">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>
<joint name="hind_right_leg_joint3">
<commandInterfaceType name="position">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</commandInterfaceType>
<commandInterfaceType name="effort">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</commandInterfaceType>
<commandInterfaceType>Kp</commandInterfaceType>
<commandInterfaceType>Kd</commandInterfaceType>
<commandInterfaceType>effort_limit</commandInterfaceType>
<stateInterfaceType>position</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>effort</stateInterfaceType>
<stateInterfaceType>coil_resistance</stateInterfaceType>
<stateInterfaceType>contact_information</stateInterfaceType>
<stateInterfaceType>timestamp</stateInterfaceType>
</joint>

<sensor name="sensor1">
<classType>ros2_control_components/IMUSensor</classType>
<stateInterfaceType>orientation</stateInterfaceType>
<stateInterfaceType>velocity</stateInterfaceType>
<stateInterfaceType>acceleration</stateInterfaceType>
<param name="min">-54</param>
<param name="max">23</param>
<param name="min_acceleration_value">-10</param>
<param name="max_acceleration_value">10</param>
</sensor>

</ros2_control>
```