Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
  • Loading branch information
Williangalvani committed Oct 11, 2024
1 parent ef31c67 commit cd1ff08
Show file tree
Hide file tree
Showing 2 changed files with 50 additions and 34 deletions.
83 changes: 49 additions & 34 deletions core/frontend/src/components/vehiclesetup/OrientationPicker.vue
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<script lang="ts">
import * as THREE from 'three'
import { OrbitControls } from 'three/examples/jsm/controls/OrbitControls'
import { TransformControls } from 'three/examples/jsm/controls/TransformControls'
import { DRACOLoader } from 'three/examples/jsm/loaders/DRACOLoader'
import { GLTFLoader } from 'three/examples/jsm/loaders/GLTFLoader'
import { PropType } from 'vue'
Expand Down Expand Up @@ -57,6 +58,7 @@ export default {
},
data() {
return {
transformControls: undefined as TransformControls | undefined,
rotations: [
new Rotation('NONE', 0, 0, 0),
new Rotation('YAW_45', 0, 0, 45),
Expand Down Expand Up @@ -157,7 +159,7 @@ export default {
if (this.threejs_canvas) {
this.threejs_canvas.appendChild(this.renderer.domElement)
}
const controls = new OrbitControls(this.camera, this.renderer.domElement)
const orbitControls = new OrbitControls(this.camera, this.renderer.domElement)
// Add lights
const ambientLight = new THREE.AmbientLight(0xffffff, 3.5)
Expand Down Expand Up @@ -188,10 +190,18 @@ export default {
const arrowHelperZ = new THREE.ArrowHelper(new THREE.Vector3(0, 0, 5), new THREE.Vector3(0, 0, 0), 0.1, 0x0000ff)
scene.add(arrowHelperZ)
this.arrows.push(arrowHelperZ)
// Add TransformControls
this.transformControls = new TransformControls(this.camera, this.renderer.domElement)
this.transformControls.addEventListener('objectChange', (event) => {
console.log(this.object.rotation.x)
orbitControls.enabled = !event.value
})
this.transformControls.setMode('rotate')
this.transformControls.setSpace('local')
scene.add(this.transformControls)
const animate = () : void => {
requestAnimationFrame(animate)
controls.update()
orbitControls.update()
if (!this.renderer) {
return
}
Expand All @@ -216,38 +226,19 @@ export default {
this.object.rotation.x = THREE.MathUtils.degToRad(rotation.roll)
this.object.rotation.z = THREE.MathUtils.degToRad(rotation.pitch)
this.object.rotation.y = THREE.MathUtils.degToRad(rotation.yaw)
// Update the selected rotation based on the object's current rotation
const currentRotation = new Rotation(
'Custom',
THREE.MathUtils.radToDeg(this.object.rotation.x),
THREE.MathUtils.radToDeg(this.object.rotation.z),
THREE.MathUtils.radToDeg(this.object.rotation.y),
)
this.updateSelectedRotation(currentRotation)
}
},
add_vehicle_model() {
if (this.scene) {
const dracoLoader = new DRACOLoader()
dracoLoader.setDecoderPath('https://www.gstatic.com/draco/versioned/decoders/1.5.6/')
const loader = new GLTFLoader()
loader.setDRACOLoader(dracoLoader)
loader.load(
this.vehicle_model,
(gltf) => {
gltf.scene.traverse((child) => {
if (child instanceof THREE.Mesh) {
child.material = new THREE.MeshStandardMaterial({
color: 0x666666, // white
transparent: true,
opacity: 0.05,
depthTest: false,
depthWrite: true,
side: THREE.DoubleSide, // Set material to be double-sided
})
}
})
this.vehicle_obj = gltf.scene
this.scene.add(gltf.scene)
},
undefined,
(error) => {
console.error('An error occurred while loading the GLB model:', error)
},
)
}
// ... (keep existing method)
},
async add_board_model() {
if (this.scene) {
Expand All @@ -263,6 +254,11 @@ export default {
this.object = gltf.scene
this.scene.add(gltf.scene)
this.rotateObject(this.selectedRotation)
// Attach TransformControls to the loaded object
if (this.transformControls) {
this.transformControls.attach(this.object)
}
},
undefined,
(error) => {
Expand All @@ -272,8 +268,27 @@ export default {
}
},
resize() {
if (!this.threejs_canvas?.clientWidth || !this.threejs_canvas?.clientHeight) {
return
// ... (keep existing method)
},
updateSelectedRotation(rotation: Rotation) {
// Find the closest predefined rotation
const closestRotation = this.rotations.reduce((prev, curr) => {
const prevDiff = Math.abs(prev.roll - rotation.roll) + Math.abs(prev.pitch - rotation.pitch) + Math.abs(prev.yaw - rotation.yaw)
const currDiff = Math.abs(curr.roll - rotation.roll) + Math.abs(curr.pitch - rotation.pitch) + Math.abs(curr.yaw - rotation.yaw)
return prevDiff < currDiff ? prev : curr
})
this.selectedRotation = closestRotation
// Update the parameter
if (this.parameter) {
mavlink2rest.setParam(
this.parameter.name,
this.rotations.indexOf(closestRotation),
autopilot_data.system_id,
this.parameter.paramType.type,
)
autopilot_data.setRebootRequired(true)
}
this.camera.aspect = this.threejs_canvas.clientWidth / this.threejs_canvas.clientHeight
this.camera.updateProjectionMatrix()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
v-model="dialog"
persistent
width="500"
@click:outside="cleanup"
>
<template #activator="{ on, attrs }">
<v-btn
Expand Down

0 comments on commit cd1ff08

Please sign in to comment.