Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added compatibility for the older SpaceMouse model #29

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
64 changes: 45 additions & 19 deletions deoxys/deoxys/utils/io_devices/spacemouse.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,7 @@ def __init__(
print("Opening SpaceMouse device")
self.device = hid.device()
self.device.open(vendor_id, product_id) # SpaceMouse
self.product_id = product_id

self.pos_sensitivity = pos_sensitivity
self.rot_sensitivity = rot_sensitivity
Expand Down Expand Up @@ -219,25 +220,50 @@ def run(self):
d = self.device.read(13)
if d is not None and self._enabled:

if d[0] == 1: ## readings from 6-DoF sensor
self.y = convert(d[1], d[2])
self.x = convert(d[3], d[4])
self.z = convert(d[5], d[6]) * -1.0

self.roll = convert(d[7], d[8])
self.pitch = convert(d[9], d[10])
self.yaw = convert(d[11], d[12])

self._control = [
self.x,
self.y,
self.z,
self.roll,
self.pitch,
self.yaw,
]

elif d[0] == 3: ## readings from the side buttons
if self.product_id == 50741:
## logic for older spacemouse model

if d[0] == 1: ## readings from 6-DoF sensor
self.y = convert(d[1], d[2])
self.x = convert(d[3], d[4])
self.z = convert(d[5], d[6]) * -1.0

elif d[0] == 2:

self.roll = convert(d[1], d[2])
self.pitch = convert(d[3], d[4])
self.yaw = convert(d[5], d[6])

self._control = [
self.x,
self.y,
self.z,
self.roll,
self.pitch,
self.yaw,
]
else:
## default logic for all other spacemouse models

if d[0] == 1: ## readings from 6-DoF sensor
self.y = convert(d[1], d[2])
self.x = convert(d[3], d[4])
self.z = convert(d[5], d[6]) * -1.0

self.roll = convert(d[7], d[8])
self.pitch = convert(d[9], d[10])
self.yaw = convert(d[11], d[12])

self._control = [
self.x,
self.y,
self.z,
self.roll,
self.pitch,
self.yaw,
]

if d[0] == 3: ## readings from the side buttons

# press left button
if d[1] == 1:
Expand Down