diff --git a/python/example_robot_data/robots_loader.py b/python/example_robot_data/robots_loader.py index 0f9a64e654d0c0f1297cf1dab84ebf1227800fbc..80fe67706b903c31267328ec75542d6472eb4cb3 100644 --- a/python/example_robot_data/robots_loader.py +++ b/python/example_robot_data/robots_loader.py @@ -189,6 +189,11 @@ class Z1Loader(RobotLoader): srdf_filename = "z1.srdf" ref_posture = "arm_up" +class B1Z1Loader(B1Loader): + urdf_filename = "b1-z1.urdf" + srdf_filename = "b1-z1.srdf" + ref_posture = "standing_with_arm_home" + class ANYmalLoader(RobotLoader): path = "anymal_b_simple_description" urdf_filename = "anymal.urdf" @@ -525,6 +530,7 @@ ROBOTS = { "go1": Go1Loader, "a1": A1Loader, "z1": Z1Loader, + "b1_z1": B1Z1Loader, "anymal": ANYmalLoader, "anymal_c": ANYmalCLoader, "anymal_kinova": ANYmalKinovaLoader, diff --git a/robots/b1_description/srdf/b1-z1.srdf b/robots/b1_description/srdf/b1-z1.srdf new file mode 100644 index 0000000000000000000000000000000000000000..09dfd91d5922ec763b83ba61784cc989dfa5aaa0 --- /dev/null +++ b/robots/b1_description/srdf/b1-z1.srdf @@ -0,0 +1,507 @@ +<?xml version="1.0" encoding="UTF-8"?> +<!--This does not replace URDF, and is not an extension of URDF. + This is a format for representing semantic information about the robot structure. + A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined +--> +<robot name="b1_description"> + <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> + <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> + <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> + <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> + <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> + <group name="lf_leg"> + <joint name="FL_hip_joint"/> + <joint name="FL_thigh_joint"/> + <joint name="FL_calf_joint"/> + </group> + <group name="lh_leg"> + <joint name="RL_hip_joint"/> + <joint name="RL_thigh_joint"/> + <joint name="RL_calf_joint"/> + </group> + <group name="rf_leg"> + <joint name="FR_hip_joint"/> + <joint name="FR_thigh_joint"/> + <joint name="FR_calf_joint"/> + </group> + <group name="rh_leg"> + <joint name="RR_hip_joint"/> + <joint name="RR_thigh_joint"/> + <joint name="RR_calf_joint"/> + </group> + <group name="arm"> + <joint name="joint1" /> + <joint name="joint2" /> + <joint name="joint3" /> + <joint name="joint4" /> + <joint name="joint5" /> + <joint name="joint6" /> + <chain base_link="base" tip_link="gripperMover" /> + </group> + <group name="all_legs"> + <group name="lf_leg"/> + <group name="lh_leg"/> + <group name="rf_leg"/> + <group name="rh_leg"/> + </group> + <group name="r_legs"> + <group name="rf_leg"/> + <group name="rh_leg"/> + </group> + <group name="l_legs"> + <group name="lf_leg"/> + <group name="lh_leg"/> + </group> + <group name="f_legs"> + <group name="lf_leg"/> + <group name="rf_leg"/> + </group> + <group name="h_legs"> + <group name="lh_leg"/> + <group name="rh_leg"/> + </group> + <group name="ld_legs"> + <group name="lf_leg"/> + <group name="rh_leg"/> + </group> + <group name="rd_legs"> + <group name="rf_leg"/> + <group name="lh_leg"/> + </group> + <group name="whole_body"> + <joint name="root_joint"/> + <joint name="FL_hip_joint"/> + <joint name="FL_thigh_joint"/> + <joint name="FL_calf_joint"/> + <joint name="FR_hip_joint"/> + <joint name="FR_thigh_joint"/> + <joint name="FR_calf_joint"/> + <joint name="RL_hip_joint"/> + <joint name="RL_thigh_joint"/> + <joint name="RL_calf_joint"/> + <joint name="RR_hip_joint"/> + <joint name="RR_thigh_joint"/> + <joint name="RR_calf_joint"/> + </group> + <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> + <group_state name="standing_with_arm_up" group="whole_body"> + <joint name="root_joint" value="0. 0. 0.55 0. 0. 0. 1."/> + <joint name="FL_calf_joint" value="-1.6"/> + <joint name="FL_hip_joint" value="0"/> + <joint name="FL_thigh_joint" value="0.8"/> + <joint name="FR_calf_joint" value="-1.6"/> + <joint name="FR_hip_joint" value="0"/> + <joint name="FR_thigh_joint" value="0.8"/> + <joint name="RL_calf_joint" value="-1.6"/> + <joint name="RL_hip_joint" value="0"/> + <joint name="RL_thigh_joint" value="0.8"/> + <joint name="RR_calf_joint" value="-1.6"/> + <joint name="RR_hip_joint" value="0"/> + <joint name="RR_thigh_joint" value="0.8"/> + <joint name="joint1" value="0." /> + <joint name="joint2" value="0.26178" /> + <joint name="joint3" value="-0.26178" /> + <joint name="joint4" value="0." /> + <joint name="joint5" value="0." /> + <joint name="joint6" value="0." /> + </group_state> + <group_state name="standing_with_arm_home" group="whole_body"> + <joint name="root_joint" value="0. 0. 0.55 0. 0. 0. 1."/> + <joint name="FL_calf_joint" value="-1.6"/> + <joint name="FL_hip_joint" value="0"/> + <joint name="FL_thigh_joint" value="0.8"/> + <joint name="FR_calf_joint" value="-1.6"/> + <joint name="FR_hip_joint" value="0"/> + <joint name="FR_thigh_joint" value="0.8"/> + <joint name="RL_calf_joint" value="-1.6"/> + <joint name="RL_hip_joint" value="0"/> + <joint name="RL_thigh_joint" value="0.8"/> + <joint name="RR_calf_joint" value="-1.6"/> + <joint name="RR_hip_joint" value="0"/> + <joint name="RR_thigh_joint" value="0.8"/> + <joint name="joint1" value="0." /> + <joint name="joint2" value="0." /> + <joint name="joint3" value="0." /> + <joint name="joint4" value="0." /> + <joint name="joint5" value="0." /> + <joint name="joint6" value="0." /> + </group_state> + <!--END EFFECTOR: Purpose: Represent information about an end effector.--> + <end_effector name="lf_foot" parent_link="FL_foot" group="lf_leg"/> + <end_effector name="rf_foot" parent_link="FR_foot" group="rf_leg"/> + <end_effector name="lh_foot" parent_link="RL_foot" group="lh_leg"/> + <end_effector name="rh_foot" parent_link="RR_foot" group="rh_leg"/> + <end_effector name="end_effector" parent_link="gripperMover" group="arm" /> + <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> + <virtual_joint name="root_joint" type="floating" parent_frame="world_frame" child_link="base"/> + <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> + <disable_collisions link1="FL_calf" link2="FL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FL_foot" reason="Adjacent"/> + <disable_collisions link1="FL_calf" link2="FL_hip" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FL_thigh" reason="Adjacent"/> + <disable_collisions link1="FL_calf" link2="FL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FL_foot" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FL_hip" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FL_thigh" reason="Adjacent"/> + <disable_collisions link1="FL_calf_rotor" link2="FL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_calf" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_foot" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_calf_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="FL_foot" link2="FL_hip" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FL_thigh" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_foot" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_foot" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FL_thigh" reason="Adjacent"/> + <disable_collisions link1="FL_hip" link2="FL_thigh_rotor" reason="Adjacent"/> + <disable_collisions link1="FL_hip" link2="FR_calf" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_foot" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FL_hip" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_hip" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_hip" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="FL_hip_rotor" link2="FL_thigh" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_calf" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_foot" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_hip_rotor" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="FL_thigh" link2="FL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_calf" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_foot" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FL_thigh_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="FR_calf" link2="FR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="FR_foot" reason="Adjacent"/> + <disable_collisions link1="FR_calf" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FR_calf" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="FR_thigh" reason="Adjacent"/> + <disable_collisions link1="FR_calf" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="FR_foot" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="FR_thigh" reason="Adjacent"/> + <disable_collisions link1="FR_calf_rotor" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_calf_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="FR_foot" link2="FR_hip" reason="Never"/> + <disable_collisions link1="FR_foot" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FR_foot" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_foot" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_hip" link2="FR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="FR_thigh" reason="Adjacent"/> + <disable_collisions link1="FR_hip" link2="FR_thigh_rotor" reason="Adjacent"/> + <disable_collisions link1="FR_hip" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FR_hip" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_hip" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_hip" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="FR_hip_rotor" link2="FR_thigh" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_hip_rotor" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="FR_thigh" link2="FR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_calf" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="FR_thigh_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="RL_calf" link2="RL_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RL_foot" reason="Adjacent"/> + <disable_collisions link1="RL_calf" link2="RL_hip" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RL_thigh" reason="Adjacent"/> + <disable_collisions link1="RL_calf" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_calf" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RL_foot" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RL_hip" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RL_thigh" reason="Adjacent"/> + <disable_collisions link1="RL_calf_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_calf_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="RL_foot" link2="RL_hip" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_foot" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_foot" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RL_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RL_thigh" reason="Adjacent"/> + <disable_collisions link1="RL_hip" link2="RL_thigh_rotor" reason="Adjacent"/> + <disable_collisions link1="RL_hip" link2="RR_calf" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_foot" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RL_hip" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_hip" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_hip" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="RL_hip_rotor" link2="RL_thigh" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_hip_rotor" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="RL_thigh" link2="RL_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_thigh" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_calf" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RL_thigh_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="RR_calf" link2="RR_calf_rotor" reason="Never"/> + <disable_collisions link1="RR_calf" link2="RR_foot" reason="Adjacent"/> + <disable_collisions link1="RR_calf" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RR_calf" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RR_calf" link2="RR_thigh" reason="Adjacent"/> + <disable_collisions link1="RR_calf" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RR_calf" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="RR_foot" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="RR_thigh" reason="Adjacent"/> + <disable_collisions link1="RR_calf_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_calf_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="RR_foot" link2="RR_hip" reason="Never"/> + <disable_collisions link1="RR_foot" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RR_foot" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RR_foot" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RR_foot" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_hip" link2="RR_hip_rotor" reason="Never"/> + <disable_collisions link1="RR_hip" link2="RR_thigh" reason="Adjacent"/> + <disable_collisions link1="RR_hip" link2="RR_thigh_rotor" reason="Adjacent"/> + <disable_collisions link1="RR_hip" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_hip" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="RR_hip_rotor" link2="RR_thigh" reason="Never"/> + <disable_collisions link1="RR_hip_rotor" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RR_hip_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_hip_rotor" link2="trunk" reason="Adjacent"/> + <disable_collisions link1="RR_thigh" link2="RR_thigh_rotor" reason="Never"/> + <disable_collisions link1="RR_thigh" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_thigh_rotor" link2="imu_link" reason="Never"/> + <disable_collisions link1="RR_thigh_rotor" link2="trunk" reason="Default"/> + <disable_collisions link1="imu_link" link2="trunk" reason="Adjacent"/> +</robot> diff --git a/robots/b1_description/urdf/b1-z1.urdf b/robots/b1_description/urdf/b1-z1.urdf new file mode 100644 index 0000000000000000000000000000000000000000..94ec59a25c81d475da92b56a61f8382717a2d13f --- /dev/null +++ b/robots/b1_description/urdf/b1-z1.urdf @@ -0,0 +1,1256 @@ +<?xml version="1.0" ?> +<!-- =================================================================================== --> +<!-- | This document was autogenerated by xacro from robot.xacro | --> +<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- =================================================================================== --> +<robot name="b1_description"> + <material name="grey"> + <color rgba="0.2 0.2 0.2 1.0"/> + </material> + <material name="silver"> + <color rgba="0.6980 0.7529 0.8392 1"/> + </material> + <material name="light_blue"> + <color rgba="0.6980 0.7529 0.8392 1"/> + </material> + <material name="dark_blue"> + <color rgba="0.5569 0.6313 0.7479 1"/> + </material> + <link name="base"> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.001 0.001 0.001"/> + </geometry> + </visual> + </link> + <joint name="floating_base" type="fixed"> + <origin rpy="0 0 0" xyz="0 0 0"/> + <parent link="base"/> + <child link="trunk"/> + </joint> + <link name="trunk"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/trunk.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.647 0.3 0.15"/> + </geometry> + </collision> + <!-- <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://b1_description/meshes/trunk.dae" scale="1 1 1"/> + </geometry> + </collision> --> + <inertial> + <origin rpy="0 0 0" xyz="0.008987 0.002243 0.003013"/> + <mass value="25"/> + <inertia ixx="0.183142146" ixy="-0.001379002" ixz="-0.027956055" iyy="0.756327752" iyz="0.000193774" izz="0.783777558"/> + </inertial> + </link> + <joint name="imu_joint" type="fixed"> + <parent link="trunk"/> + <child link="imu_link"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + </joint> + <link name="imu_link"> + <inertial> + <mass value="0.001"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.001 0.001 0.001"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size=".001 .001 .001"/> + </geometry> + </collision> + </link> + <joint name="FR_hip_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0.3455 -0.072 0"/> + <parent link="trunk"/> + <child link="FR_hip"/> + <axis xyz="1 0 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/> + </joint> + <joint name="FR_hip_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.1955 -0.072 0"/> + <parent link="trunk"/> + <child link="FR_hip_rotor"/> + </joint> + <link name="FR_hip"> + <visual> + <origin rpy="3.141592653589793 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/hip.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/> + <geometry> + <cylinder length="0.04" radius="0.09"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.020298 -0.009758 0.000109"/> + <mass value="2.1"/> + <inertia ixx="0.00406608" ixy="0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/> + </inertial> + </link> + <link name="FR_hip_rotor"> + <visual> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.199"/> + <inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/> + </inertial> + </link> + <joint name="FR_thigh_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 -0.12675 0"/> + <parent link="FR_hip"/> + <child link="FR_thigh"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/> + </joint> + <joint name="FR_thigh_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 -0.00935 0"/> + <parent link="FR_hip"/> + <child link="FR_thigh_rotor"/> + </joint> + <link name="FR_thigh"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/thigh_mirror.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.05 0.08"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/> + <mass value="3.934"/> + <inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/> + </inertial> + </link> + <link name="FR_thigh_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="FR_calf_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="FR_thigh"/> + <child link="FR_calf"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/> + </joint> + <joint name="FR_calf_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 0.0519 0"/> + <parent link="FR_thigh"/> + <child link="FR_calf_rotor"/> + </joint> + <link name="FR_calf"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/calf.dae" scale="1 1 1"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.04 0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/> + <mass value="0.857"/> + <inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/> + </inertial> + </link> + <link name="FR_calf_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="FR_foot_fixed" type="fixed"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="FR_calf"/> + <child link="FR_foot"/> + </joint> + <link name="FR_foot"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.04"/> + </geometry> + </collision> + <inertial> + <mass value="0.05"/> + <inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/> + </inertial> + </link> + <transmission name="FR_hip_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FR_hip_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FR_hip_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="FR_thigh_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FR_thigh_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FR_thigh_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="FR_calf_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FR_calf_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FR_calf_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <joint name="FL_hip_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0.3455 0.072 0"/> + <parent link="trunk"/> + <child link="FL_hip"/> + <axis xyz="1 0 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/> + </joint> + <joint name="FL_hip_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.1955 0.072 0"/> + <parent link="trunk"/> + <child link="FL_hip_rotor"/> + </joint> + <link name="FL_hip"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/hip.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/> + <geometry> + <cylinder length="0.04" radius="0.09"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.020298 0.009758 0.000109"/> + <mass value="2.1"/> + <inertia ixx="0.00406608" ixy="-0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/> + </inertial> + </link> + <link name="FL_hip_rotor"> + <visual> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.199"/> + <inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/> + </inertial> + </link> + <joint name="FL_thigh_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0.12675 0"/> + <parent link="FL_hip"/> + <child link="FL_thigh"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/> + </joint> + <joint name="FL_thigh_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 0.00935 0"/> + <parent link="FL_hip"/> + <child link="FL_thigh_rotor"/> + </joint> + <link name="FL_thigh"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/thigh.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.05 0.08"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/> + <mass value="3.934"/> + <inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/> + </inertial> + </link> + <link name="FL_thigh_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="FL_calf_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="FL_thigh"/> + <child link="FL_calf"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/> + </joint> + <joint name="FL_calf_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 -0.0519 0"/> + <parent link="FL_thigh"/> + <child link="FL_calf_rotor"/> + </joint> + <link name="FL_calf"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/calf.dae" scale="1 1 1"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.04 0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/> + <mass value="0.857"/> + <inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/> + </inertial> + </link> + <link name="FL_calf_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="FL_foot_fixed" type="fixed"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="FL_calf"/> + <child link="FL_foot"/> + </joint> + <link name="FL_foot"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.04"/> + </geometry> + </collision> + <inertial> + <mass value="0.05"/> + <inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/> + </inertial> + </link> + <transmission name="FL_hip_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FL_hip_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FL_hip_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="FL_thigh_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FL_thigh_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FL_thigh_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="FL_calf_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="FL_calf_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="FL_calf_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <joint name="RR_hip_joint" type="revolute"> + <origin rpy="0 0 0" xyz="-0.3455 -0.072 0"/> + <parent link="trunk"/> + <child link="RR_hip"/> + <axis xyz="1 0 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/> + </joint> + <joint name="RR_hip_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="-0.1955 -0.072 0"/> + <parent link="trunk"/> + <child link="RR_hip_rotor"/> + </joint> + <link name="RR_hip"> + <visual> + <origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/hip.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/> + <geometry> + <cylinder length="0.04" radius="0.09"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.020298 -0.009758 0.000109"/> + <mass value="2.1"/> + <inertia ixx="0.00406608" ixy="-0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/> + </inertial> + </link> + <link name="RR_hip_rotor"> + <visual> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.199"/> + <inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/> + </inertial> + </link> + <joint name="RR_thigh_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 -0.12675 0"/> + <parent link="RR_hip"/> + <child link="RR_thigh"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/> + </joint> + <joint name="RR_thigh_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 -0.00935 0"/> + <parent link="RR_hip"/> + <child link="RR_thigh_rotor"/> + </joint> + <link name="RR_thigh"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/thigh_mirror.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.05 0.08"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/> + <mass value="3.934"/> + <inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/> + </inertial> + </link> + <link name="RR_thigh_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="RR_calf_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="RR_thigh"/> + <child link="RR_calf"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/> + </joint> + <joint name="RR_calf_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 0.0519 0"/> + <parent link="RR_thigh"/> + <child link="RR_calf_rotor"/> + </joint> + <link name="RR_calf"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/calf.dae" scale="1 1 1"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.04 0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/> + <mass value="0.857"/> + <inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/> + </inertial> + </link> + <link name="RR_calf_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="RR_foot_fixed" type="fixed"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="RR_calf"/> + <child link="RR_foot"/> + </joint> + <link name="RR_foot"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.04"/> + </geometry> + </collision> + <inertial> + <mass value="0.05"/> + <inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/> + </inertial> + </link> + <transmission name="RR_hip_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RR_hip_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RR_hip_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="RR_thigh_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RR_thigh_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RR_thigh_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="RR_calf_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RR_calf_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RR_calf_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <joint name="RL_hip_joint" type="revolute"> + <origin rpy="0 0 0" xyz="-0.3455 0.072 0"/> + <parent link="trunk"/> + <child link="RL_hip"/> + <axis xyz="1 0 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/> + </joint> + <joint name="RL_hip_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="-0.1955 0.072 0"/> + <parent link="trunk"/> + <child link="RL_hip_rotor"/> + </joint> + <link name="RL_hip"> + <visual> + <origin rpy="0 3.141592653589793 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/hip.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/> + <geometry> + <cylinder length="0.04" radius="0.09"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.020298 0.009758 0.000109"/> + <mass value="2.1"/> + <inertia ixx="0.00406608" ixy="0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/> + </inertial> + </link> + <link name="RL_hip_rotor"> + <visual> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.199"/> + <inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/> + </inertial> + </link> + <joint name="RL_thigh_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0.12675 0"/> + <parent link="RL_hip"/> + <child link="RL_thigh"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/> + </joint> + <joint name="RL_thigh_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 0.00935 0"/> + <parent link="RL_hip"/> + <child link="RL_thigh_rotor"/> + </joint> + <link name="RL_thigh"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/thigh.dae" scale="1 1 1"/> + </geometry> + <material name="silver"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.05 0.08"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/> + <mass value="3.934"/> + <inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/> + </inertial> + </link> + <link name="RL_thigh_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="RL_calf_joint" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="RL_thigh"/> + <child link="RL_calf"/> + <axis xyz="0 1 0"/> + <dynamics damping="0" friction="0"/> + <limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/> + </joint> + <joint name="RL_calf_rotor_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.0 -0.0519 0"/> + <parent link="RL_thigh"/> + <child link="RL_calf_rotor"/> + </joint> + <link name="RL_calf"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/b1_description/meshes/calf.dae" scale="1 1 1"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/> + <geometry> + <box size="0.35 0.04 0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/> + <mass value="0.857"/> + <inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/> + </inertial> + </link> + <link name="RL_calf_rotor"> + <visual> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.02" radius="0.05"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> + <mass value="0.266"/> + <inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/> + </inertial> + </link> + <joint name="RL_foot_fixed" type="fixed"> + <origin rpy="0 0 0" xyz="0 0 -0.35"/> + <parent link="RL_calf"/> + <child link="RL_foot"/> + </joint> + <link name="RL_foot"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.04"/> + </geometry> + </collision> + <inertial> + <mass value="0.05"/> + <inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/> + </inertial> + </link> + + + + <joint name="z1_static_joint" type="fixed"> + <origin rpy="0 0 0" xyz="0.35 0 0.09"/> + <parent link="trunk"/> + <child link="link00"/> + </joint> + <link name="link00"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link00.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <collision> + <geometry> + <cylinder length="0.051" radius="0.0325"/> + </geometry> + <origin rpy="0 0 0" xyz="0 0 0.0255"/> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.00334984 -0.00013615 0.02495843"/> + <mass value="0.47247481"/> + <inertia ixx="0.00037937" ixy="-3.5e-07" ixz="-1.037e-05" iyy="0.00041521" iyz="-9.9e-07" izz="0.00053066"/> + </inertial> + </link> + <joint name="joint1" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 0.0585"/> + <parent link="link00"/> + <child link="link01"/> + <axis xyz="0 0 1"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30.0" lower="-2.6179938779914944" upper="2.6179938779914944" velocity="3.1415"/> + </joint> + <link name="link01"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link01.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="2.47e-06 -0.00025198 0.02317169"/> + <mass value="0.67332551"/> + <inertia ixx="0.00128328" ixy="-6e-08" ixz="-4e-07" iyy="0.00071931" iyz="5e-07" izz="0.00083936"/> + </inertial> + </link> + <joint name="joint2" type="revolute"> + <origin rpy="0 0 0" xyz="0 0 0.045"/> + <parent link="link01"/> + <child link="link02"/> + <axis xyz="0 1 0"/> + <dynamics damping="2.0" friction="2.0"/> + <limit effort="60.0" lower="0.0" upper="2.9670597283903604" velocity="3.1415"/> + </joint> + <link name="link02"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link02.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <collision> + <geometry> + <cylinder length="0.102" radius="0.0325"/> + </geometry> + <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> + </collision> + <collision> + <geometry> + <cylinder length="0.235" radius="0.0225"/> + </geometry> + <origin rpy="0 1.5707963267948966 0" xyz="-0.16249999999999998 0 0"/> + </collision> + <collision> + <geometry> + <cylinder length="0.051" radius="0.0325"/> + </geometry> + <origin rpy="1.5707963267948966 0 0" xyz="-0.35 0 0"/> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.11012601 0.00240029 0.00158266"/> + <mass value="1.19132258"/> + <inertia ixx="0.00102138" ixy="0.00062358" ixz="5.13e-06" iyy="0.02429457" iyz="-2.1e-06" izz="0.02466114"/> + </inertial> + </link> + <joint name="joint3" type="revolute"> + <origin rpy="0 0 0" xyz="-0.35 0 0"/> + <parent link="link02"/> + <child link="link03"/> + <axis xyz="0 1 0"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30.0" lower="-2.8797932657906435" upper="0.0" velocity="3.1415"/> + </joint> + <link name="link03"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link03.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <collision> + <geometry> + <cylinder length="0.116" radius="0.02"/> + </geometry> + <origin rpy="0 1.5707963267948966 0" xyz="0.128 0 0.055"/> + </collision> + <collision> + <geometry> + <cylinder length="0.059" radius="0.0325"/> + </geometry> + <origin rpy="0 1.5707963267948966 1.5707963267948966" xyz="0.2205 0 0.055"/> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.10609208 -0.00541815 0.03476383"/> + <mass value="0.83940874"/> + <inertia ixx="0.00108061" ixy="-8.669e-05" ixz="-0.00208102" iyy="0.00954238" iyz="-1.332e-05" izz="0.00886621"/> + </inertial> + </link> + <joint name="joint4" type="revolute"> + <origin rpy="0 0 0" xyz="0.218 0 0.057"/> + <parent link="link03"/> + <child link="link04"/> + <axis xyz="0 1 0"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30.0" lower="-1.5184364492350666" upper="1.5184364492350666" velocity="3.1415"/> + </joint> + <link name="link04"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link04.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <collision> + <geometry> + <cylinder length="0.067" radius="0.0325"/> + </geometry> + <origin rpy="0 0 0" xyz="0.072 0 0"/> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.04366681 0.00364738 -0.00170192"/> + <mass value="0.56404563"/> + <inertia ixx="0.00031576" ixy="8.13e-05" ixz="4.091e-05" iyy="0.00092996" iyz="-5.96e-06" izz="0.00097912"/> + </inertial> + </link> + <joint name="joint5" type="revolute"> + <origin rpy="0 0 0" xyz="0.07 0.0 0.0"/> + <parent link="link04"/> + <child link="link05"/> + <axis xyz="0 0 1"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30.0" lower="-1.3439035240356338" upper="1.3439035240356338" velocity="3.1415"/> + </joint> + <link name="link05"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link05.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0.03121533 0.0 0.00646316"/> + <mass value="0.38938492"/> + <inertia ixx="0.00017605" ixy="4e-07" ixz="5.689e-05" iyy="0.00055896" iyz="-1.3e-07" izz="0.0005386"/> + </inertial> + </link> + <joint name="joint6" type="revolute"> + <origin rpy="0 0 0" xyz="0.0492 0.0 0.0"/> + <parent link="link05"/> + <child link="link06"/> + <axis xyz="1 0 0"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30.0" lower="-2.792526803190927" upper="2.792526803190927" velocity="3.1415"/> + </joint> + <link name="link06"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_Link06.dae" scale="1 1 1"/> + </geometry> + <material name="light_blue"/> + </visual> + <collision> + <geometry> + <cylinder length="0.051" radius="0.0325"/> + </geometry> + <origin rpy="0 1.5707963267948966 0" xyz="0.0255 0 0"/> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.0241569 -0.00017355 -0.00143876"/> + <mass value="0.28875807"/> + <inertia ixx="0.00018328" ixy="1.22e-06" ixz="5.4e-07" iyy="0.0001475" iyz="8e-08" izz="0.0001468"/> + </inertial> + </link> + <joint name="gripperStator" type="fixed"> + <origin rpy="0 0 0" xyz="0.051 0.0 0.0"/> + <parent link="link06"/> + <child link="gripperStator"/> + </joint> + <link name="gripperStator"> + <visual> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_GripperStator.dae" scale="1 1 1"/> + </geometry> + <material name="dark_blue"/> + </visual> + <collision> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/collision/z1_GripperStator.STL" scale="1 1 1"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.04764427 -0.00035819 -0.00249162"/> + <mass value="0.52603655"/> + <inertia ixx="0.00038683" ixy="-0.00000359" ixz="0.00007662" iyy="0.00068614" iyz="0.00000209" izz="0.00066293"/> + </inertial> + </link> + <joint name="jointGripper" type="revolute"> + <origin rpy="0 0 0" xyz="0.049 0.0 0"/> + <parent link="gripperStator"/> + <child link="gripperMover"/> + <axis xyz="0 1 0"/> + <dynamics damping="1.0" friction="1.0"/> + <limit effort="30." velocity="3.1415" lower="-1.5707" upper="0.0"/> + </joint> + <link name="gripperMover"> + <visual> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/visual/z1_GripperMover.dae" scale="1 1 1"/> + </geometry> + <material name="dark_blue"/> + </visual> + <collision> + <geometry> + <mesh filename="package://example-robot-data/robots/z1_description/meshes/collision/z1_GripperMover.STL" scale="1 1 1"/> + </geometry> + </collision> + <inertial> + <origin rpy="0 0 0" xyz="0.01320633 0.00476708 0.00380534"/> + <mass value="0.27621302"/> + <inertia ixx="0.00017716" ixy="0.00001683" ixz="-0.00001786" iyy="0.00026787" iyz="0.00000262" izz="0.00035728"/> + </inertial> + </link> + + + + + + + <transmission name="RL_hip_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RL_hip_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RL_hip_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="RL_thigh_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RL_thigh_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RL_thigh_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="RL_calf_tran"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="RL_calf_joint"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="RL_calf_motor"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans1"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans2"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans3"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint3"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator3"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans4"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint4"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator4"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans5"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint5"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator5"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <transmission name="JointTrans6"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint6"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="Actuator6"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> +</robot>