Skip to content

Commit 3753b5b

Browse files
committed
Add configuration files for using the sw layer that handles the coupling
See: - #178 - robotology/yarp#3026 - robotology/yarp#3085
1 parent a6828bd commit 3753b5b

9 files changed

+182
-2
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
<?xml version="1.0" encoding="UTF-8" ?>
2+
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<robot name="ergocubGazebo" build="1" portprefix="/ergocubSim" xmlns:xi="http://www.w3.org/2001/XInclude">
5+
6+
<devices>
7+
8+
<!-- MOTOR CONTROLLERS -->
9+
<xi:include href="wrappers/motorControl/left_arm-mc_wrapper.xml" />
10+
<xi:include href="wrappers/motorControl/right_arm-mc_wrapper.xml" />
11+
<xi:include href="wrappers/motorControl/left_leg-mc_wrapper.xml" />
12+
<xi:include href="wrappers/motorControl/right_leg-mc_wrapper.xml" />
13+
<xi:include href="wrappers/motorControl/head-mc_wrapper.xml" />
14+
<xi:include href="wrappers/motorControl/torso-mc_wrapper.xml" />
15+
16+
<xi:include href="wrappers/motorControl/left_hand-coupling_handler.xml" />
17+
<xi:include href="wrappers/motorControl/right_hand-coupling_handler.xml" />
18+
<xi:include href="wrappers/motorControl/left_arm-mc_remapper-coupling.xml" />
19+
<xi:include href="wrappers/motorControl/right_arm-mc_remapper-coupling.xml" />
20+
<xi:include href="wrappers/motorControl/left_arm-mc_remapper.xml" />
21+
<xi:include href="wrappers/motorControl/right_arm-mc_remapper.xml" />
22+
<xi:include href="wrappers/motorControl/left_leg-mc_remapper.xml" />
23+
<xi:include href="wrappers/motorControl/right_leg-mc_remapper.xml" />
24+
<xi:include href="wrappers/motorControl/head-mc_remapper.xml" />
25+
<xi:include href="wrappers/motorControl/torso-mc_remapper.xml" />
26+
27+
<xi:include href="wrappers/motorControl/all-mc_remapper-coupling.xml" />
28+
<xi:include href="wrappers/motorControl/all-mc_remapper_ros2-coupling.xml" />
29+
<!-- ANALOG SENSORS FT -->
30+
<xi:include href="wrappers/FT/left_leg-FT_remapper.xml" />
31+
<xi:include href="wrappers/FT/right_leg-FT_remapper.xml" />
32+
<xi:include href="wrappers/FT/left_leg-FT_wrapper.xml" />
33+
<xi:include href="wrappers/FT/right_leg-FT_wrapper.xml" />
34+
<xi:include href="wrappers/FT/left_arm-FT_wrapper.xml" />
35+
<xi:include href="wrappers/FT/right_arm-FT_wrapper.xml" />
36+
37+
<!-- INERTIAL SENSOR-->
38+
<xi:include href="wrappers/inertials/head-inertials_wrapper.xml" />
39+
40+
<!-- HEAD SENSORS -->
41+
<xi:include href="sensors/rgbd_camera_wrapper.xml" />
42+
<xi:include href="sensors/rgbd_camera_wrapper_ros2.xml" />
43+
<xi:include href="sensors/lidar_wrapper.xml" />
44+
<xi:include href="sensors/lidar_wrapper_ros2.xml" />
45+
46+
</devices>
47+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="alljoints_mc-coupling" type="controlboardremapper">
5+
<!-- These are the parameters with torso_pitch removed -->
6+
<param name="axesNames">(neck_pitch,neck_roll,neck_yaw,camera_tilt,l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,l_wrist_yaw,l_wrist_roll,l_wrist_pitch,l_thumb_add,l_thumb_prox,l_thumb_dist,l_index_add,l_index_prox,l_index_dist,l_middle_prox,l_middle_dist,l_ring_prox,l_ring_dist,l_pinkie_prox,l_pinkie_dist,r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow,r_wrist_yaw,r_wrist_roll,r_wrist_pitch,r_thumb_add,r_thumb_prox,r_thumb_dist,r_index_add,r_index_prox,r_index_dist,r_middle_prox,r_middle_dist,r_ring_prox,r_ring_dist,r_pinkie_prox,r_pinkie_dist,torso_roll,torso_pitch,torso_yaw,l_hip_pitch,l_hip_roll,l_hip_yaw,l_knee,l_ankle_pitch,l_ankle_roll,r_hip_pitch,r_hip_roll,r_hip_yaw,r_knee,r_ankle_pitch,r_ankle_roll)</param>
7+
<param name="period"> 0.010 </param>
8+
<param name="joints"> 57 </param>
9+
<action phase="startup" level="6" type="attach">
10+
<paramlist name="networks">
11+
<elem name="head_joints"> head-mc_remapper </elem>
12+
<elem name="left_arm_joints"> left_arm-mc_remapper-coupling </elem>
13+
<elem name="right_arm_joints"> right_arm-mc_remapper-coupling </elem>
14+
<elem name="torso_joints"> torso-mc_remapper </elem>
15+
<elem name="left_leg_joints"> left_leg-mc_remapper </elem>
16+
<elem name="right_leg_joints"> right_leg-mc_remapper </elem>
17+
</paramlist>
18+
</action>
19+
<action phase="shutdown" level="20" type="detach" />
20+
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
<?xml version="1.0" encoding="UTF-8" ?>
2+
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="cbw_ros2" type="controlBoard_nws_ros2">
5+
<param name="node_name"> ros2_cb_node </param>
6+
<param name="topic_name"> /joint_states </param>
7+
<param name="period"> 0.010 </param>
8+
<action phase="startup" level="10" type="attach">
9+
<param name="device"> alljoints_mc-coupling </param>
10+
</action>
11+
<action phase="shutdown" level="15" type="detach" />
12+
</device>

urdf/ergoCub/conf/wrappers/motorControl/all-mc_remapper_ros2.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,8 @@
55
<param name="node_name"> ros2_cb_node </param>
66
<param name="topic_name"> /joint_states </param>
77
<param name="period"> 0.010 </param>
8-
<action phase="startup" level="7" type="attach">
8+
<action phase="startup" level="10" type="attach">
99
<param name="device"> alljoints_mc </param>
1010
</action>
11-
<action phase="shutdown" level="3" type="detach" />
11+
<action phase="shutdown" level="15" type="detach" />
1212
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm-mc_remapper-coupling" type="controlboardremapper">
5+
<param name="axesNames">(l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,l_wrist_yaw,l_wrist_roll,l_wrist_pitch,l_thumb_add,l_thumb_prox,l_thumb_dist,l_index_add,l_index_prox,l_index_dist,l_middle_prox,l_middle_dist,l_ring_prox,l_ring_dist,l_pinkie_prox,l_pinkie_dist)</param>
6+
<param name="joints"> 19 </param>
7+
<action phase="startup" level="6" type="attach">
8+
<paramlist name="networks">
9+
<elem name="left_arm_joints1"> left_arm_hardware_device </elem>
10+
<elem name="left_arm_joints2"> left_hand-coupling_handler </elem>
11+
</paramlist>
12+
</action>
13+
<action phase="shutdown" level="20" type="detach" />
14+
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_hand-coupling_handler" type="controlBoardCouplingHandler">
5+
<param name="coupling_device"> couplingXCubHandMk5 </param>
6+
<param name="jointNames"> l_thumb_add l_thumb_prox l_thumb_dist l_index_add l_index_prox l_index_dist l_middle_prox l_middle_dist l_ring_prox l_ring_dist l_pinkie_prox l_pinkie_dist </param>
7+
<group name="LIMITS">
8+
<param name="jntVelMax"> 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 </param>
9+
<param name="jntPosMax"> 100.0 90.0 101.4 15.0 90.0 103.1 90.0 103.1 90.0 103.1 90.0 98.7 </param>
10+
<param name="jntPosMin"> -100.0 -90.0 -101.4 -15.0 -90.0 -103.1 -90.0 -103.1 -90.0 -103.1 -90.0 -98.7 </param>
11+
</group>
12+
<group name="COUPLING">
13+
<param name="actuatedAxesNames"> l_thumb_add l_thumb_oc l_index_add l_index_oc l_middle_oc l_ring_pinky_oc </param>
14+
<param name="actuatedAxesPosMin"> 0.0 0.0 0.0 0.0 0.0 0.0 </param>
15+
<param name="actuatedAxesPosMax"> 100.0 90.0 15.0 90.0 90.0 90.0 </param>
16+
</group>
17+
<group name="COUPLING_PARAMS">
18+
<param name="L0x"> -0.0050 -0.0050 -0.0050 -0.0050 -0.0050 </param>
19+
<param name="L0y"> 0.0040 0.0040 0.0040 0.0040 0.0040 </param>
20+
<param name="q2bias"> -173.35 -173.35 -173.35 -173.35 -170.53 </param>
21+
<param name="q1off"> 2.45 2.15 2.15 2.15 2.46 </param>
22+
<param name="k"> 0.03415 0.03913 0.03913 0.03913 0.03418 </param>
23+
<param name="d"> 0.03503 0.04003 0.04003 0.04003 0.03503 </param>
24+
<param name="l"> 0.00604 0.00604 0.00604 0.00604 0.00608 </param>
25+
<param name="b"> 0.00640 0.00640 0.00640 0.00640 0.00640 </param>
26+
</group>
27+
<action phase="startup" level="5" type="attach">
28+
<param name="device"> left_hand_hardware_device </param>
29+
</action>
30+
<action phase="shutdown" level="15" type="detach" />
31+
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_hand-mc_nws_yarp" type="controlBoard_nws_yarp">
5+
<param name="name"> ${portprefix}/left_hand </param>
6+
<param name="period">0.01</param>
7+
<action phase="startup" level="10" type="attach">
8+
<param name="device"> left_hand-coupling_handler </param>
9+
</action>
10+
<action phase="shutdown" level="15" type="detach" />
11+
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="right_arm-mc_remapper-coupling" type="controlboardremapper">
5+
<param name="axesNames">(r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow,r_wrist_yaw,r_wrist_roll,r_wrist_pitch,r_thumb_add,r_thumb_prox,r_thumb_dist,r_index_add,r_index_prox,r_index_dist,r_middle_prox,r_middle_dist,r_ring_prox,r_ring_dist,r_pinkie_prox,r_pinkie_dist)</param>
6+
<param name="joints"> 19 </param>
7+
<action phase="startup" level="6" type="attach">
8+
<paramlist name="networks">
9+
<elem name="right_arm_joints1"> right_arm_hardware_device </elem>
10+
<elem name="right_arm_joints2"> right_hand-coupling_handler </elem>
11+
</paramlist>
12+
</action>
13+
<action phase="shutdown" level="20" type="detach" />
14+
</device>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
3+
4+
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="right_hand-coupling_handler" type="controlBoardCouplingHandler">
5+
<param name="coupling_device"> couplingXCubHandMk5 </param>
6+
<param name="jointNames"> r_thumb_add r_thumb_prox r_thumb_dist r_index_add r_index_prox r_index_dist r_middle_prox r_middle_dist r_ring_prox r_ring_dist r_pinkie_prox r_pinkie_dist </param>
7+
<group name="LIMITS">
8+
<param name="jntVelMax"> 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 </param>
9+
<param name="jntPosMax"> 100.0 90.0 101.4 15.0 90.0 103.1 90.0 103.1 90.0 103.1 90.0 98.7 </param>
10+
<param name="jntPosMin"> -100.0 -90.0 -101.4 -15.0 -90.0 -103.1 -90.0 -103.1 -90.0 -103.1 -90.0 -98.7 </param>
11+
</group>
12+
<group name="COUPLING">
13+
<param name="actuatedAxesNames"> r_thumb_add r_thumb_oc r_index_add r_index_oc r_middle_oc r_ring_pinky_oc </param>
14+
<param name="actuatedAxesPosMin"> 0.0 0.0 0.0 0.0 0.0 0.0 </param>
15+
<param name="actuatedAxesPosMax"> 100.0 90.0 15.0 90.0 90.0 90.0 </param>
16+
</group>
17+
<group name="COUPLING_PARAMS">
18+
<param name="L0x"> -0.0050 -0.0050 -0.0050 -0.0050 -0.0050 </param>
19+
<param name="L0y"> 0.0040 0.0040 0.0040 0.0040 0.0040 </param>
20+
<param name="q2bias"> -173.35 -173.35 -173.35 -173.35 -170.53 </param>
21+
<param name="q1off"> 2.45 2.15 2.15 2.15 2.46 </param>
22+
<param name="k"> 0.03415 0.03913 0.03913 0.03913 0.03418 </param>
23+
<param name="d"> 0.03503 0.04003 0.04003 0.04003 0.03503 </param>
24+
<param name="l"> 0.00604 0.00604 0.00604 0.00604 0.00608 </param>
25+
<param name="b"> 0.00640 0.00640 0.00640 0.00640 0.00640 </param>
26+
</group>
27+
<action phase="startup" level="5" type="attach">
28+
<param name="device"> right_hand_hardware_device </param>
29+
</action>
30+
<action phase="shutdown" level="15" type="detach" />
31+
</device>

0 commit comments

Comments
 (0)