ros2_control
ros2_control copied to clipboard
Component parser: Get mimic information from URDF
I started implementing the parsing of information about mimic joints from the URDF (instead of duplicating information in the ros2_control
tag).
This will fix #652:
After a discussion with @destogl it seems we converged on a solution very close to the above.
Overview: Using a mimic joint should work out-of-the-box, on by default. Users who want to opt-in can do so in the configuration of their hardware component. The mimic property should be defined in the wider URDF section, not under the
<ros2_control>
tag.In the example with the setup below,
ros2_control
should do the check on each joint to figure out if it is a mimic joint or not. This could be part ofJointInfo
(will need to reach up to the full urdf to find it) ((implementation detail))<joint name="right_finger_joint" type="prismatic"> <axis xyz="0 1 0"/> <origin xyz="0.0 -0.48 1" rpy="0.0 0.0 0.0"/> <parent link="base"/> <child link="finger_right"/> <limit effort="1000.0" lower="0" upper="0.38" velocity="10"/> </joint> <joint name="left_finger_joint" type="prismatic"> <mimic joint="right_finger_joint" multiplier="1" offset="0"/> <axis xyz="0 1 0"/> <origin xyz="0.0 0.48 1" rpy="0.0 0.0 3.1415926535"/> <parent link="base"/> <child link="finger_left"/> <limit effort="1000.0" lower="0" upper="0.38" velocity="10"/> </joint> <ros2_control> <joint name="right_finger_joint"> <command_interface name="effort"/> <state_interface name="position"/> <state_interface name="velocity"/> <state_interface name="effort"/> </joint> <joint name="left_finger_joint"> <command_interface name="position"/> <state_interface name="position"/> <state_interface name="velocity"/> <state_interface name="effort"/> </joint> </ros2_control>
If one wants to disable mimic behaviour for some reason, they can still turn this functionality off by adding
mimic="false"
to the joint like so<joint name="left_finger_joint" mimic="false"> <command_interface name="position"/> <state_interface name="position"/> <state_interface name="velocity"/> <state_interface name="effort"/> </joint>
Originally posted by @bmagyar in https://github.com/ros-controls/ros2_control/issues/652#issuecomment-1106224121
Decisions in WG meeting on 2024 01 03:
- [x]
mimic="false"
should be for opt-out; missing ormimic="true"
has the same effect - [x] component_parser throws an error if an invalid URDF is given. Additionally, I added a check if a
joint
defined in the ros2_control tag is available in the URDF and throw an error otherwise. Is this ok, or are there any use-cases for an incomplete URDF? - [x] As a consequence of the above point: The tests failed, because there are some interfaces like "configuration/max_tcp_jerk" defined as joint. IMHO we should use the semantic information of the type and changed them to be of
gpio
type.
Codecov Report
Attention: Patch coverage is 89.23077%
with 7 lines
in your changes are missing coverage. Please review.
Project coverage is 76.14%. Comparing base (
35bb5f7
) to head (3a1c1cd
). Report is 15 commits behind head on master.
:exclamation: Current head 3a1c1cd differs from pull request most recent head 931f108. Consider uploading reports for the commit 931f108 to get more accurate results
Additional details and impacted files
@@ Coverage Diff @@
## master #1256 +/- ##
==========================================
+ Coverage 75.51% 76.14% +0.63%
==========================================
Files 41 41
Lines 3328 3396 +68
Branches 1921 1957 +36
==========================================
+ Hits 2513 2586 +73
+ Misses 421 420 -1
+ Partials 394 390 -4
Flag | Coverage Δ | |
---|---|---|
unittests | 76.14% <89.23%> (+0.63%) |
:arrow_up: |
Flags with carried forward coverage won't be shown. Click here to find out more.
Files | Coverage Δ | |
---|---|---|
...terface/include/mock_components/generic_system.hpp | 100.00% <ø> (ø) |
|
...e_interface/src/mock_components/generic_system.cpp | 79.18% <100.00%> (-1.17%) |
:arrow_down: |
hardware_interface/src/component_parser.cpp | 92.83% <88.88%> (-0.42%) |
:arrow_down: |
This pull request is in conflict. Could you fix it @christophfroehlich?
This pull request is in conflict. Could you fix it @christophfroehlich?
This pull request is in conflict. Could you fix it @christophfroehlich?
This pull request is in conflict. Could you fix it @christophfroehlich?
Niceee! Thanks for fixing it. Can we get this merged soon? I have 2 more PRs waiting for these changes.
@bence @destogl Let's merge this and then https://github.com/ros-controls/control.ros.org/pull/262 to put the migration notes on the top level of the docs.
Say no more!