torso, arms added, working on leg rolling joint
parent
e27b8d9132
commit
e13ab81d8a
|
|
@ -17,8 +17,8 @@ export class URDFEditor {
|
||||||
this.scene = new THREE.Scene();
|
this.scene = new THREE.Scene();
|
||||||
this.scene.background = new THREE.Color(0xaaaaaa);
|
this.scene.background = new THREE.Color(0xaaaaaa);
|
||||||
|
|
||||||
this.camera = new THREE.PerspectiveCamera(45, canvas.clientWidth / canvas.clientHeight, 0.1, 100);
|
this.camera = new THREE.PerspectiveCamera(60, canvas.clientWidth / canvas.clientHeight, 0.1, 100);
|
||||||
this.camera.position.set(2, 2, 2);
|
this.camera.position.set(-0.3, 0.5, -0.7);
|
||||||
this.camera.lookAt(0, 0, 0);
|
this.camera.lookAt(0, 0, 0);
|
||||||
|
|
||||||
this.renderer = new THREE.WebGLRenderer({ canvas, antialias: true });
|
this.renderer = new THREE.WebGLRenderer({ canvas, antialias: true });
|
||||||
|
|
@ -38,7 +38,7 @@ export class URDFEditor {
|
||||||
|
|
||||||
|
|
||||||
this.controls = new OrbitControls(this.camera, this.renderer.domElement);
|
this.controls = new OrbitControls(this.camera, this.renderer.domElement);
|
||||||
this.controls.target.set(0, 0.5, 0);
|
this.controls.target.set(0, 0.1, 0);
|
||||||
this.controls.update();
|
this.controls.update();
|
||||||
|
|
||||||
this.raycaster = new THREE.Raycaster();
|
this.raycaster = new THREE.Raycaster();
|
||||||
|
|
@ -230,6 +230,7 @@ export class URDFEditor {
|
||||||
console.log(lower, upper);
|
console.log(lower, upper);
|
||||||
|
|
||||||
const jointTransmission = this.robot.joints[jointName].transmission;
|
const jointTransmission = this.robot.joints[jointName].transmission;
|
||||||
|
if (!jointTransmission) return;
|
||||||
const encoderRange = jointTransmission.encoderRange / jointTransmission.mechanicalReduction;
|
const encoderRange = jointTransmission.encoderRange / jointTransmission.mechanicalReduction;
|
||||||
const sector = createRotationSector(this.worldAxis, lower, upper, encoderRange);
|
const sector = createRotationSector(this.worldAxis, lower, upper, encoderRange);
|
||||||
const indicator = createAngleIndicator(this.worldAxis, this.jointAngles[jointName] ?? 0);
|
const indicator = createAngleIndicator(this.worldAxis, this.jointAngles[jointName] ?? 0);
|
||||||
|
|
@ -342,6 +343,10 @@ function radiansToTicks(radians, actuator) {
|
||||||
|
|
||||||
function getJointLimits(jointName, robot) {
|
function getJointLimits(jointName, robot) {
|
||||||
const transmission = robot.joints[jointName].transmission;
|
const transmission = robot.joints[jointName].transmission;
|
||||||
|
|
||||||
|
if (!transmission) {
|
||||||
|
return { lower: -Math.PI, upper: Math.PI };
|
||||||
|
}
|
||||||
//console.log(transmission.encoderValidMin, transmission.encoderValidMax);
|
//console.log(transmission.encoderValidMin, transmission.encoderValidMax);
|
||||||
const lowerRad = ticksToRadians(transmission.encoderValidMin, transmission);
|
const lowerRad = ticksToRadians(transmission.encoderValidMin, transmission);
|
||||||
const upperRad = ticksToRadians(transmission.encoderValidMax, transmission);
|
const upperRad = ticksToRadians(transmission.encoderValidMax, transmission);
|
||||||
|
|
|
||||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
|
@ -3,14 +3,15 @@
|
||||||
<joint name="base_joint" type="fixed">
|
<joint name="base_joint" type="fixed">
|
||||||
<parent link="base_footprint" />
|
<parent link="base_footprint" />
|
||||||
<child link="base_link" />
|
<child link="base_link" />
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0.11" rpy="0 0 0" />
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
<link name="base_link">
|
<link name="base_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.05 0.05" />
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Torso.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="base_link-material">
|
<material name="base_link-material">
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
||||||
|
|
@ -25,50 +26,23 @@
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<mass value="1" />
|
<mass value="1" />
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0"
|
||||||
|
izz="0.16666666666666666" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
<joint name="base_link_to_spine_1" type="revolute">
|
<joint name="base_link_to_upper_arm_right" type="revolute">
|
||||||
<parent link="base_link" />
|
<parent link="base_link" />
|
||||||
<child link="spine_1"/>
|
|
||||||
<origin xyz="0 0 0.0337" rpy="0 0 0"/>
|
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
<link name="spine_1">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.1 0.05 0.1" />
|
|
||||||
</geometry>
|
|
||||||
<material name="spine_1-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.1 0.05 0.1" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<mass value="1" />
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
<joint name="spine_1_to_upper_arm_right" type="revolute">
|
|
||||||
<parent link="spine_1"/>
|
|
||||||
<child link="upper_arm_right" />
|
<child link="upper_arm_right" />
|
||||||
<origin xyz="0.0624 0 0.0973" rpy="-3.1416 -0.6587 0"/>
|
<origin xyz="0.04 0 0.048" rpy="0 0 0" />
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229" />
|
<axis xyz="-0.9997 -0.0114 0.0229" />
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
<link name="upper_arm_right">
|
<link name="upper_arm_right">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.03 0.03 0.06" />
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Arm_Right.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="upper_arm_right-material">
|
<material name="upper_arm_right-material">
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
||||||
|
|
@ -83,82 +57,27 @@
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||||
<mass value="1" />
|
<mass value="1" />
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0"
|
||||||
</inertial>
|
izz="0.16666666666666666" />
|
||||||
</link>
|
|
||||||
<joint name="upper_arm_right_to_lower_arm_right" type="revolute">
|
|
||||||
<parent link="upper_arm_right"/>
|
|
||||||
<child link="lower_arm_right"/>
|
|
||||||
<origin xyz="0.0 0 .065" rpy="0 0 0"/>
|
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
<link name="lower_arm_right">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.05" />
|
|
||||||
</geometry>
|
|
||||||
<material name="lower_arm_right-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.05" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
||||||
<mass value="1" />
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
<joint name="lower_arm_right_to_hand_right" type="revolute">
|
|
||||||
<parent link="lower_arm_right"/>
|
|
||||||
<child link="hand_right"/>
|
|
||||||
<origin xyz="0 0 0.055" rpy="0 0 0"/>
|
|
||||||
<axis xyz="0 1 0"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
<link name="hand_right">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.03" />
|
|
||||||
</geometry>
|
|
||||||
<material name="hand_right-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.03" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
||||||
<mass value="1" />
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<!-- Left Upper Arm -->
|
<!-- Left Upper Arm -->
|
||||||
<joint name="spine_1_to_upper_arm_left" type="revolute">
|
<joint name="base_link_to_upper_arm_left" type="revolute">
|
||||||
<parent link="spine_1"/>
|
<parent link="base_link" />
|
||||||
<child link="upper_arm_left" />
|
<child link="upper_arm_left" />
|
||||||
<origin xyz="-0.0624 0 0.0973" rpy="3.1416 0.6587 0"/>
|
<origin xyz="-0.04 0 0.048" rpy="0 0 0" />
|
||||||
<axis xyz="-1 0 0" />
|
<axis xyz="-1 0 0" />
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="upper_arm_left">
|
<link name="upper_arm_left">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0.03" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.03 0.03 0.06"/>
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Arm_Left.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="upper_arm_left-material">
|
<material name="upper_arm_left-material">
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
||||||
|
|
@ -173,92 +92,57 @@
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||||
<mass value="1" />
|
<mass value="1" />
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0"
|
||||||
|
izz="0.16666666666666666" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
<joint name="base_link_to_hip_right" type="revolute">
|
||||||
<!-- Left Lower Arm -->
|
|
||||||
<joint name="upper_arm_left_to_lower_arm_left" type="revolute">
|
|
||||||
<parent link="upper_arm_left"/>
|
|
||||||
<child link="lower_arm_left"/>
|
|
||||||
<origin xyz="0.0 0 0.065" rpy="0 0 0"/>
|
|
||||||
<axis xyz="-1 0 0"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
<link name="lower_arm_left">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.05"/>
|
|
||||||
</geometry>
|
|
||||||
<material name="lower_arm_left-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.05"/>
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
||||||
<mass value="1"/>
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
|
|
||||||
|
|
||||||
<!-- Left Hand -->
|
|
||||||
<joint name="lower_arm_left_to_hand_left" type="revolute">
|
|
||||||
<parent link="lower_arm_left"/>
|
|
||||||
<child link="hand_left"/>
|
|
||||||
<origin xyz="0 0 0.055" rpy="0 0 0"/>
|
|
||||||
<axis xyz="0 1 0"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
|
|
||||||
<link name="hand_left">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.03"/>
|
|
||||||
</geometry>
|
|
||||||
<material name="hand_left-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.03"/>
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
||||||
<mass value="1"/>
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
<joint name="base_link_to_upper_leg_right" type="revolute">
|
|
||||||
<parent link="base_link" />
|
<parent link="base_link" />
|
||||||
<child link="upper_leg_right" />
|
<child link="hip_right" />
|
||||||
<origin xyz="0.035 0 -0.035" rpy="0 0 0" />
|
<origin xyz="0.024 0.005 -0.023" rpy="0 0 0" />
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="0 0 1" />
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/> </joint>
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
|
</joint>
|
||||||
<link name="upper_leg_right">
|
<link name="hip_right">
|
||||||
<visual>
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Hip_Right.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
|
</geometry>
|
||||||
|
<material name="upper_leg_right-material">
|
||||||
|
<color rgba="0.0021 0.0497 0.4851 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
<origin xyz="0 0 -0.035" rpy="0 0 0" />
|
<origin xyz="0 0 -0.035" rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.04 0.04 0.07" />
|
<box size="0.04 0.04 0.07" />
|
||||||
</geometry>
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 -0.035" rpy="0 0 0" />
|
||||||
|
<mass value="1" />
|
||||||
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667" />
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="hip_right_to_upper_leg_right" type="revolute">
|
||||||
|
<parent link="hip_right" />
|
||||||
|
<child link="upper_leg_right" />
|
||||||
|
<origin xyz="0.009 0.0 -0.023" rpy="0 0 0" />
|
||||||
|
<axis xyz="1 0 0" />
|
||||||
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="upper_leg_right">
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Upper_Leg_Right.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
|
</geometry>
|
||||||
<material name="upper_leg_right-material">
|
<material name="upper_leg_right-material">
|
||||||
<color rgba="0.0021 0.0497 0.4851 1" />
|
<color rgba="0.0021 0.0497 0.4851 1" />
|
||||||
</material>
|
</material>
|
||||||
|
|
@ -280,17 +164,18 @@
|
||||||
<joint name="upper_leg_right_to_lower_leg_right" type="revolute">
|
<joint name="upper_leg_right_to_lower_leg_right" type="revolute">
|
||||||
<parent link="upper_leg_right" />
|
<parent link="upper_leg_right" />
|
||||||
<child link="lower_leg_right" />
|
<child link="lower_leg_right" />
|
||||||
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
|
<origin xyz="-0.001 0.0075 -0.0575" rpy="-0.14 0 0" />
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
<axis xyz="-1 0 0" />
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
<link name="lower_leg_right">
|
<link name="lower_leg_right">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.04 0.04 0.07"/>
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Lower_Leg_Right.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="lower_leg_right-material">
|
<material name="lower_leg_right-material">
|
||||||
<color rgba="0.0021 0.0497 0.4851 1" />
|
<color rgba="0.0021 0.0497 0.4851 1" />
|
||||||
|
|
@ -342,8 +227,6 @@
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
<!-- Left Upper Leg -->
|
<!-- Left Upper Leg -->
|
||||||
<joint name="base_link_to_upper_leg_left" type="revolute">
|
<joint name="base_link_to_upper_leg_left" type="revolute">
|
||||||
<parent link="base_link" />
|
<parent link="base_link" />
|
||||||
|
|
@ -443,53 +326,45 @@
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<joint name="spine_1_to_neck" type="revolute">
|
<!-- Spine to yaw joint -->
|
||||||
<parent link="spine_1"/>
|
<joint name="base_link_to_neck_yaw" type="revolute">
|
||||||
<child link="neck"/>
|
<parent link="base_link" />
|
||||||
<origin xyz="0 0 0.12" rpy="0 0 0"/>
|
<child link="neck_yaw_link" />
|
||||||
<axis xyz="0 0 1"/>
|
<origin xyz="0 0 0.065" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 0 1" /> <!-- yaw/pan around Z -->
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
|
<link name="neck_yaw_link" />
|
||||||
|
|
||||||
<link name="neck">
|
<!-- Pitch joint -->
|
||||||
<visual>
|
<joint name="neck_pitch" type="revolute">
|
||||||
|
<parent link="neck_yaw_link" />
|
||||||
|
<child link="neck_pitch_link" />
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<geometry>
|
<axis xyz="1 0 0" /> <!-- pitch around X -->
|
||||||
<box size="0.03 0.03 0.03" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</geometry>
|
</joint>
|
||||||
<material name="neck-material">
|
<link name="neck_pitch_link" />
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.03 0.03 0.03" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
||||||
<mass value="1" />
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
|
|
||||||
<joint name="neck_to_head" type="revolute">
|
<!-- Roll joint -->
|
||||||
<parent link="neck"/>
|
<joint name="neck_roll" type="revolute">
|
||||||
|
<parent link="neck_pitch_link" />
|
||||||
<child link="head" />
|
<child link="head" />
|
||||||
<origin xyz="0 0 0.04" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 1 0" /> <!-- roll around Y -->
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
<!-- Head (includes fused neck geometry) -->
|
||||||
<link name="head">
|
<link name="head">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
<origin xyz="0 0 0" rpy="-1.5745 3.149 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Face.glb" scale="0.001 0.001 0.001"/>
|
<mesh filename="package://Little_Sophia_Face/meshes/Little_Sophia_Face.glb"
|
||||||
|
scale="0.001 0.001 0.001" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="head-material">
|
<material name="head-material">
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
<color rgba="0.002 0.05 0.48 1" />
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
|
|
@ -501,14 +376,14 @@
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<mass value="1" />
|
<mass value="1" />
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
<inertia ixx="0.16" ixy="0" ixz="0" iyy="0.16" iyz="0" izz="0.16" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<transmission name="spine_1_trans">
|
<transmission name="upper_arm_left">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="base_link_to_spine_1">
|
<joint name="base_joint">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -520,10 +395,9 @@
|
||||||
<encoderRange>270</encoderRange>
|
<encoderRange>270</encoderRange>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="upper_arm_left">
|
<transmission name="upper_arm_left">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_upper_arm_left">
|
<joint name="base_link_to_upper_arm_left">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -568,7 +442,7 @@
|
||||||
|
|
||||||
<transmission name="upper_arm_right">
|
<transmission name="upper_arm_right">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_upper_arm_right">
|
<joint name="base_link_to_upper_arm_right">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -581,27 +455,13 @@
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="lower_arm_right">
|
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
|
||||||
<joint name="upper_arm_right_to_lower_arm_right">
|
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
||||||
</joint>
|
|
||||||
<actuator name="spine_motor_1">
|
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
||||||
<encoderTicks>4096</encoderTicks>
|
|
||||||
<encoderValidMin>200</encoderValidMin>
|
|
||||||
<encoderValidMax>3500</encoderValidMax>
|
|
||||||
<encoderRange>270</encoderRange>
|
|
||||||
</actuator>
|
|
||||||
</transmission>
|
|
||||||
|
|
||||||
<transmission name="hand_right">
|
<transmission name="hip_right">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="lower_arm_right_to_hand_right">
|
<joint name="base_link_to_hip_right">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="hip_right">
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
<encoderTicks>4096</encoderTicks>
|
<encoderTicks>4096</encoderTicks>
|
||||||
|
|
@ -700,12 +560,13 @@
|
||||||
<encoderRange>270</encoderRange>
|
<encoderRange>270</encoderRange>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
<transmission name="neck_base">
|
<!-- Yaw (pan) transmission -->
|
||||||
|
<transmission name="neck_yaw_trans">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_neck">
|
<joint name="base_link_to_neck_yaw">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="neck_motor_base">
|
<actuator name="neck_motor_yaw">
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
<encoderTicks>4096</encoderTicks>
|
<encoderTicks>4096</encoderTicks>
|
||||||
|
|
@ -714,12 +575,14 @@
|
||||||
<encoderRange>270</encoderRange>
|
<encoderRange>270</encoderRange>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
<transmission name="neck_tip">
|
|
||||||
|
<!-- Pitch transmission -->
|
||||||
|
<transmission name="neck_pitch_trans">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="neck_to_head">
|
<joint name="neck_pitch">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="neck_motor_tip">
|
<actuator name="neck_motor_pitch">
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
<encoderTicks>4096</encoderTicks>
|
<encoderTicks>4096</encoderTicks>
|
||||||
|
|
@ -729,4 +592,21 @@
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Roll transmission -->
|
||||||
|
<transmission name="neck_roll_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="neck_roll">
|
||||||
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="neck_motor_roll">
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
|
<encoderTicks>4096</encoderTicks>
|
||||||
|
<encoderValidMin>500</encoderValidMin>
|
||||||
|
<encoderValidMax>4095</encoderValidMax>
|
||||||
|
<encoderRange>270</encoderRange>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
@ -28,42 +28,15 @@
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
<joint name="base_link_to_spine_1" type="revolute">
|
<joint name="base_link_to_base_link" type="revolute">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link"/>
|
||||||
<child link="spine_1"/>
|
<child link="base_link"/>
|
||||||
<origin xyz="0 0 0.0337" rpy="0 0 0"/>
|
<origin xyz="0 0 0.0337" rpy="0 0 0"/>
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
||||||
</joint>
|
</joint>
|
||||||
<link name="spine_1">
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.1 0.05 0.1" />
|
|
||||||
</geometry>
|
|
||||||
<material name="spine_1-material">
|
|
||||||
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<box size="0.1 0.05 0.1" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<inertial>
|
|
||||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
||||||
<mass value="1" />
|
|
||||||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
<joint name="spine_1_to_upper_arm_right" type="revolute">
|
|
||||||
<parent link="spine_1"/>
|
|
||||||
<child link="upper_arm_right"/>
|
|
||||||
<origin xyz="0.0624 0 0.0973" rpy="-3.1416 -0.6587 0"/>
|
|
||||||
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
||||||
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
||||||
</joint>
|
|
||||||
<link name="upper_arm_right">
|
<link name="upper_arm_right">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||||
|
|
@ -146,8 +119,8 @@
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<!-- Left Upper Arm -->
|
<!-- Left Upper Arm -->
|
||||||
<joint name="spine_1_to_upper_arm_left" type="revolute">
|
<joint name="base_link_to_upper_arm_left" type="revolute">
|
||||||
<parent link="spine_1"/>
|
<parent link="base_link"/>
|
||||||
<child link="upper_arm_left"/>
|
<child link="upper_arm_left"/>
|
||||||
<origin xyz="-0.0624 0 0.0973" rpy="3.1416 0.6587 0"/>
|
<origin xyz="-0.0624 0 0.0973" rpy="3.1416 0.6587 0"/>
|
||||||
<axis xyz="-1 0 0"/>
|
<axis xyz="-1 0 0"/>
|
||||||
|
|
@ -443,8 +416,8 @@
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<joint name="spine_1_to_neck" type="revolute">
|
<joint name="base_link_to_neck" type="revolute">
|
||||||
<parent link="spine_1"/>
|
<parent link="base_link"/>
|
||||||
<child link="neck"/>
|
<child link="neck"/>
|
||||||
<origin xyz="0 0 0.12" rpy="0 0 0"/>
|
<origin xyz="0 0 0.12" rpy="0 0 0"/>
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
|
|
@ -506,9 +479,9 @@
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
||||||
<transmission name="spine_1_trans">
|
<transmission name="base_link_trans">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="base_link_to_spine_1">
|
<joint name="base_link_to_base_link">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -523,7 +496,7 @@
|
||||||
|
|
||||||
<transmission name="upper_arm_left">
|
<transmission name="upper_arm_left">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_upper_arm_left">
|
<joint name="base_link_to_upper_arm_left">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -568,7 +541,7 @@
|
||||||
|
|
||||||
<transmission name="upper_arm_right">
|
<transmission name="upper_arm_right">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_upper_arm_right">
|
<joint name="base_link_to_upper_arm_right">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="spine_motor_1">
|
<actuator name="spine_motor_1">
|
||||||
|
|
@ -702,7 +675,7 @@
|
||||||
</transmission>
|
</transmission>
|
||||||
<transmission name="neck_base">
|
<transmission name="neck_base">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="spine_1_to_neck">
|
<joint name="base_link_to_neck">
|
||||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="neck_motor_base">
|
<actuator name="neck_motor_base">
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue