sl-firmware b2c9f368f6 feat: VESC CAN telemetry for dual motors (Issue #645)
New saltybot_vesc_telemetry ROS2 package — SocketCAN (python-can, can0)
telemetry for dual FSESC 6.7 Pro (FW 6.6) on CAN IDs 61 (left) and 79 (right).

- vesc_can_protocol.py: STATUS/STATUS_4/STATUS_5 frame parsers, VescState
  dataclass, GET_VALUES request builder (CAN_PACKET_PROCESS_SHORT_BUFFER)
- vesc_telemetry_node.py: ROS2 node; background CAN RX thread; publishes
  /vesc/left/state, /vesc/right/state, /vesc/combined (JSON String msgs),
  /diagnostics (DiagnosticArray); overcurrent/overtemp/fault alerting;
  configurable poll rate 10-50 Hz (default 20 Hz)
- test_vesc_telemetry.py: 31 unit tests, all passing (no ROS/CAN required)
- config/vesc_telemetry_params.yaml, launch file

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 09:53:09 -04:00

28 lines
893 B
Python

from setuptools import setup
package_name = "saltybot_vesc_telemetry"
setup(
name=package_name,
version="0.1.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", [f"resource/{package_name}"]),
(f"share/{package_name}", ["package.xml"]),
(f"share/{package_name}/launch", ["launch/vesc_telemetry.launch.py"]),
(f"share/{package_name}/config", ["config/vesc_telemetry_params.yaml"]),
],
install_requires=["setuptools", "python-can"],
zip_safe=True,
maintainer="sl-firmware",
maintainer_email="sl-firmware@saltylab.local",
description="VESC CAN telemetry node for dual FSESC 6.7 Pro",
license="MIT",
tests_require=["pytest"],
entry_points={
"console_scripts": [
"vesc_telemetry_node = saltybot_vesc_telemetry.vesc_telemetry_node:main",
],
},
)