API review
Proposer: John Hsu
Present at review:
- List reviewers
Changes
The ability to specify Joints without specifying Links.
Original URDF Proposal:
<link name="C"> <joint name="J" type="revolute"> <!-- transform from link to joint frame --> <!-- in old URDF, this is undefined and assumed to be identity transform --> <origin xyz="0 0 0" rpy="0 0 0"/> <!-- joint properties --> <axis xyz="0 1 0"/> <!--in the joint frame--> <parent name="P"/> <!-- in old URDF, this is in <link> not in <joint> --> <!-- <origin> is the transform from Joint Frame to Parent Link --> <!-- in old URDF, this is in <link> not in <joint><parent> --> <origin xyz="0 0 0" rpy="0 0 0"/> </parent> <joint_properties damping="1" friction="0"/> <limit lower="0.9" upper="2.1" effort="1000" velocity="1"/> <safety_controller soft_lower_limit="0.7" soft_upper_limit="2.1" k_position="1" k_velocity="1" /> <calibration reference_position="0.7" /> </joint> <inertial> <mass value="10"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1 1 1"/> </geometry> <texture name="PR2/Green"/> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1.01 1.01 1.01"/> </geometry> <contact_coefficient mu="0" resitution="0" k_p="0" k_d="0" /> </collision> </link>
New URDF Proposal:
<joint name="J" type="revolute"> <dynamics damping="1" friction="0"/> <limit lower="0.9" upper="2.1" effort="1000" velocity="1"/> <safety_controller soft_lower_limit="0.7" soft_upper_limit="2.1" k_position="1" k_velocity="1" /> <calibration reference_position="0.7" /> <axis xyz="0 1 0"/> <parent link="P"> <origin xyz="0 0 0" rpy="0 0 0"/> </parent> <child link="C"> <origin xyz="0 0 0" rpy="0 0 0"/> </child> </joint> <link name="C"> <inertial> <mass value="10"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1 1 1"/> </geometry> <texture name="PR2/Green"/> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1.01 1.01 1.01"/> </geometry> <contact_coefficient mu="0" resitution="0" k_p="0" k_d="0" /> </collision> </link>
- Making joint frame the same as link frame,
<joint name="J" type="revolute"> <dynamics damping="1" friction="0"/> <limit lower="0.9" upper="2.1" effort="1000" velocity="1"/> <safety_controller soft_lower_limit="0.7" soft_upper_limit="2.1" k_position="1" k_velocity="1" /> <calibration reference_position="0.7" /> <!-- origin: origin of the joint in the parent frame --> <!-- child link frame is the joint frame --> <!-- axis is in the joint frame --> <origin xyz="0 0 0" rpy="0 0 0"/> <axis xyz="0 1 0"/> <parent link="P"/> <child link="C"/> </joint> <link name="C"> <inertial> <mass value="10"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1 1 1"/> </geometry> <material name="Green"/> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="1.01 1.01 1.01"/> </geometry> <contact_coefficient mu="0" resitution="0" k_p="0" k_d="0" /> </collision> </link> <material name="Green"> <texture filename="...texture file..." /> <!--color rgb="255 255 255" /--> </material>
Question / concerns / comments
Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.
Meeting agenda
<joint_properties> should be <dynamics>
adding <mimic joint="Joint_name" offset="0" multiplier="1" /> under <joint>
<rpy>: clearly define transform. make sure gazebo is doing rpy not ypr.
- check for cycles, flag unsupported feature error
children should have weak_ptr pointer to parent links, use <boost::weak_ptr> and implement boost::shared_ptr<Link> GetParent()
<joint><origin/></joint>: defines the origin of the joint in the parent frame
- child link frame is the joint frame
- axis is in the joint frame
adding <material> blocks to URDF, with texture or color elements.
<material name="Green"> <texture filename="...texture file..." /> <!--color rgb="255 255 255" /--> </material>
- get collada robot sample from Rosen (John)
- setup Euler Angles Reveiew (eric)
Conclusion
Package status change mark change manifest)
Action items that need to be taken.
Major issues that need to be resolved