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.background = new THREE.Color(0xaaaaaa);
|
||||
|
||||
this.camera = new THREE.PerspectiveCamera(45, canvas.clientWidth / canvas.clientHeight, 0.1, 100);
|
||||
this.camera.position.set(2, 2, 2);
|
||||
this.camera = new THREE.PerspectiveCamera(60, canvas.clientWidth / canvas.clientHeight, 0.1, 100);
|
||||
this.camera.position.set(-0.3, 0.5, -0.7);
|
||||
this.camera.lookAt(0, 0, 0);
|
||||
|
||||
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.target.set(0, 0.5, 0);
|
||||
this.controls.target.set(0, 0.1, 0);
|
||||
this.controls.update();
|
||||
|
||||
this.raycaster = new THREE.Raycaster();
|
||||
|
|
@ -230,6 +230,7 @@ export class URDFEditor {
|
|||
console.log(lower, upper);
|
||||
|
||||
const jointTransmission = this.robot.joints[jointName].transmission;
|
||||
if (!jointTransmission) return;
|
||||
const encoderRange = jointTransmission.encoderRange / jointTransmission.mechanicalReduction;
|
||||
const sector = createRotationSector(this.worldAxis, lower, upper, encoderRange);
|
||||
const indicator = createAngleIndicator(this.worldAxis, this.jointAngles[jointName] ?? 0);
|
||||
|
|
@ -342,6 +343,10 @@ function radiansToTicks(radians, actuator) {
|
|||
|
||||
function getJointLimits(jointName, robot) {
|
||||
const transmission = robot.joints[jointName].transmission;
|
||||
|
||||
if (!transmission) {
|
||||
return { lower: -Math.PI, upper: Math.PI };
|
||||
}
|
||||
//console.log(transmission.encoderValidMin, transmission.encoderValidMax);
|
||||
const lowerRad = ticksToRadians(transmission.encoderValidMin, 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.
File diff suppressed because it is too large
Load Diff
|
|
@ -28,42 +28,15 @@
|
|||
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="base_link_to_spine_1" type="revolute">
|
||||
<joint name="base_link_to_base_link" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="spine_1"/>
|
||||
<child link="base_link"/>
|
||||
<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"/>
|
||||
<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">
|
||||
<visual>
|
||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||
|
|
@ -146,8 +119,8 @@
|
|||
</link>
|
||||
|
||||
<!-- Left Upper Arm -->
|
||||
<joint name="spine_1_to_upper_arm_left" type="revolute">
|
||||
<parent link="spine_1"/>
|
||||
<joint name="base_link_to_upper_arm_left" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="upper_arm_left"/>
|
||||
<origin xyz="-0.0624 0 0.0973" rpy="3.1416 0.6587 0"/>
|
||||
<axis xyz="-1 0 0"/>
|
||||
|
|
@ -443,8 +416,8 @@
|
|||
</link>
|
||||
|
||||
|
||||
<joint name="spine_1_to_neck" type="revolute">
|
||||
<parent link="spine_1"/>
|
||||
<joint name="base_link_to_neck" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="neck"/>
|
||||
<origin xyz="0 0 0.12" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
|
|
@ -506,9 +479,9 @@
|
|||
</link>
|
||||
|
||||
|
||||
<transmission name="spine_1_trans">
|
||||
<transmission name="base_link_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="base_link_to_spine_1">
|
||||
<joint name="base_link_to_base_link">
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="spine_motor_1">
|
||||
|
|
@ -523,7 +496,7 @@
|
|||
|
||||
<transmission name="upper_arm_left">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="spine_1_to_upper_arm_left">
|
||||
<joint name="base_link_to_upper_arm_left">
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="spine_motor_1">
|
||||
|
|
@ -568,7 +541,7 @@
|
|||
|
||||
<transmission name="upper_arm_right">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="spine_1_to_upper_arm_right">
|
||||
<joint name="base_link_to_upper_arm_right">
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="spine_motor_1">
|
||||
|
|
@ -702,7 +675,7 @@
|
|||
</transmission>
|
||||
<transmission name="neck_base">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="spine_1_to_neck">
|
||||
<joint name="base_link_to_neck">
|
||||
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="neck_motor_base">
|
||||
|
|
|
|||
Loading…
Reference in New Issue