带有SDF的AddModelFromFile()的默认端口



通过

加载的模型的默认输入和输出端口是什么?model = parser.AddModelFromFile("myfile.sdf")

?

特别是,我想知道变量的顺序是什么。我很困惑,因为我正在装载一个有10个关节的机器人,因此我希望

plant.get_state_output_port(model).size()

为20。也就是10个关节位置,10个关节速度。然而,当装载机器人时,上面的结果是16,这对我来说似乎相当奇怪。这也提出了变量如何排序的问题,即首先是所有位置还是通过关节?

我正在加载的sdf文件是:

<?xml version="1.0"?>
<sdf version="1.7">
<model name="two_planar_cc_segments">
<link name="robot_base">
<pose> 0 0 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="robot_base_col">
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</collision>
<visual name="robot_base_vis">
<material>
<diffuse>1.0 0.0 0.0 1.0</diffuse>
</material>
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</visual>
</link>
<!-- This is the first CC Segment -->
<link name="s1l0">
<pose relative_to="robot_base"> 0 0 0 1.570796327 0 0 </pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s1l0_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s1l0_vis">
<material>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s1q0" type="revolute">
<pose relative_to="robot_base"> 0 0 0 0 0 0</pose>
<parent> robot_base </parent>
<child> s1l0 </child>
<axis>
<xyz> 0 0 1 </xyz>
</axis>
</joint>
<link name="s1l1">
<pose relative_to="s1l0"> 0 0 0 0 0 0 </pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s1l1_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s1l1_vis">
<material>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s1q1" type="revolute">
<pose relative_to="s1q0">0 0 0 1.570796327 0 0 </pose>
<parent> s1l0 </parent>
<child> s1l1 </child>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<link name="s1l2">
<pose relative_to="s1l1"> 0 0 0 1.570796327 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s1l2_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s1l2_vis">
<material>
<diffuse>0.0 1.0 0.0 1.0</diffuse>
</material>
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="s1q2" type="prismatic">
<pose relative_to="s1q1">0 0 0 0 0 0 </pose>
<parent> s1l1 </parent>
<child> s1l2 </child>
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<friction>1</friction>
<damping>1</damping>
</dynamics>
<limit>
<lower>0.0</lower>
<upper>0.1</upper>
</limit>
</axis>
</joint>
<link name="s1l3">
<pose relative_to="s1l2"> 0 0 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s1l3_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s1l3_vis">
<material>
<diffuse>0.0 0.0 1.0 1.0</diffuse>
</material>
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="s1q3" type="prismatic">
<pose relative_to="s1q2">0 0 0 -1.570796327 0 0 </pose>
<parent> s1l2 </parent>
<child> s1l3 </child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<friction>1</friction>
<damping>1</damping>
</dynamics>
<limit>
<lower>0.0</lower>
<upper>0.1</upper>
</limit>
</axis>
</joint>
<link name="s1l4">
<pose relative_to="s1l3"> 0 0 0 1.570796327 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s1l4_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s1l4_vis">
<material>
<diffuse>0.0 0.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s1q4" type="revolute">
<pose relative_to="s1q3">0 0 0 0 0 0 </pose>
<parent> s1l3 </parent>
<child> s1l4 </child>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<frame name="s1-ee-link">
<pose relative_to="s1q4">0 0 0 0 0 0</pose>
</frame>
<!-- Till Here -->
<!-- This is the first CC Segment -->
<link name="s2l0">
<pose relative_to="s1l4"> 0 0 0 0 0 0 </pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s2l0_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s2l0_vis">
<material>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s2q0" type="revolute">
<pose relative_to="s1l4"> 0 0 0 1.570796327 0 0</pose>
<parent> s1l4 </parent>
<child> s2l0 </child>
<axis>
<xyz> 0 0 1 </xyz>
</axis>
</joint>
<link name="s2l1">
<pose relative_to="s2l0"> 0 0 0 0 0 0 </pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s2l1_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s2l1_vis">
<material>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s2q1" type="revolute">
<pose relative_to="s2q0">0 0 0 1.570796327 0 0 </pose>
<parent> s2l0 </parent>
<child> s2l1 </child>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<link name="s2l2">
<pose relative_to="s2l1"> 0 0 0 1.570796327 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s2l2_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s2l2_vis">
<material>
<diffuse>0.0 1.0 0.0 1.0</diffuse>
</material>
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="s2q2" type="prismatic">
<pose relative_to="s2q1">0 0 0 0 0 0 </pose>
<parent> s2l1 </parent>
<child> s2l2 </child>
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<friction>1</friction>
<damping>1</damping>
</dynamics>
<limit>
<lower>0.0</lower>
<upper>0.1</upper>
</limit>
</axis>
</joint>
<link name="s2l3">
<pose relative_to="s2l2"> 0 0 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s2l3_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s2l3_vis">
<material>
<diffuse>0.0 0.0 1.0 1.0</diffuse>
</material>
<geometry>
<cylinder>
<length> 0.0001 </length>
<radius> 0.01 </radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="s2q3" type="prismatic">
<pose relative_to="s2q2">0 0 0 -1.570796327 0 0 </pose>
<parent> s2l2 </parent>
<child> s2l3 </child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<friction>1</friction>
<damping>1</damping>
</dynamics>
<limit>
<lower>0.0</lower>
<upper>0.1</upper>
</limit>
</axis>
</joint>
<link name="s2l4">
<pose relative_to="s2l3"> 0 0 0 1.570796327 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.001</iyy>
<iyz>0.0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="s2l4_col">
<geometry>
<empty></empty>
</geometry>
</collision>
<visual name="s2l4_vis">
<material>
<diffuse>0.0 0.0 1.0 1.0</diffuse>
</material>
<geometry>
<empty></empty>
</geometry>
</visual>
</link>
<joint name="s2q4" type="revolute">
<pose relative_to="s2q3">0 0 0 0 0 0 </pose>
<parent> s2l3 </parent>
<child> s2l4 </child>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<frame name="s2-ee-link">
<pose relative_to="s2q4">0 0 0 0 0 0</pose>
</frame>
<!-- Till Here -->
</model>
</sdf>

正如徐晨所说,这是因为你的模型默认是浮动的。

如果你希望固定模型,那么你应该得到你想要的理想坐标;或者,您可能需要屏蔽您想要的dof。

示例:quick deepnote ipynb

相关内容

  • 没有找到相关文章