fix: Make VESC CAN IDs configurable, default 56/68 (Issue #667)
FSESC 6.7 Pro Mini Dual uses CAN IDs 56/68, not 61/79. Updates all driver, telemetry, and odometry bridge files to use correct defaults. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
This commit is contained in:
parent
70fa404437
commit
ee16bae9fb
@ -2,7 +2,7 @@ vesc_can_odometry:
|
|||||||
ros__parameters:
|
ros__parameters:
|
||||||
# ── CAN motor IDs (used for CAN addressing) ───────────────────────────────
|
# ── CAN motor IDs (used for CAN addressing) ───────────────────────────────
|
||||||
left_can_id: 56 # left motor VESC CAN ID
|
left_can_id: 56 # left motor VESC CAN ID
|
||||||
right_can_id: 79 # right motor VESC CAN ID
|
right_can_id: 68 # right motor VESC CAN ID
|
||||||
|
|
||||||
# ── State topic names (must match what telemetry publishes) ───────────────
|
# ── State topic names (must match what telemetry publishes) ───────────────
|
||||||
left_state_topic: /vesc/left/state
|
left_state_topic: /vesc/left/state
|
||||||
|
|||||||
@ -3,7 +3,8 @@
|
|||||||
vesc_odometry_bridge.py — Differential drive odometry from dual VESC CAN motors (Issue #646).
|
vesc_odometry_bridge.py — Differential drive odometry from dual VESC CAN motors (Issue #646).
|
||||||
|
|
||||||
Subscribes to per-motor VESC telemetry topics (configurable, defaulting to
|
Subscribes to per-motor VESC telemetry topics (configurable, defaulting to
|
||||||
/vesc/left/state and /vesc/right/state as published by the telemetry node),
|
/vesc/left/state and /vesc/right/state as published by the telemetry node)
|
||||||
|
for CAN IDs 56 (left) and 68 (right),
|
||||||
applies differential drive kinematics via DiffDriveOdometry, and publishes:
|
applies differential drive kinematics via DiffDriveOdometry, and publishes:
|
||||||
|
|
||||||
/odom nav_msgs/Odometry — consumed by Nav2 / slam_toolbox
|
/odom nav_msgs/Odometry — consumed by Nav2 / slam_toolbox
|
||||||
@ -57,7 +58,7 @@ class VESCCANOdometryNode(Node):
|
|||||||
|
|
||||||
# ── Parameters ────────────────────────────────────────────────────────
|
# ── Parameters ────────────────────────────────────────────────────────
|
||||||
self.declare_parameter("left_can_id", 56) # CAN ID for left motor
|
self.declare_parameter("left_can_id", 56) # CAN ID for left motor
|
||||||
self.declare_parameter("right_can_id", 79) # CAN ID for right motor
|
self.declare_parameter("right_can_id", 68) # CAN ID for right motor
|
||||||
# Configurable state topic names — default to the names telemetry publishes
|
# Configurable state topic names — default to the names telemetry publishes
|
||||||
self.declare_parameter("left_state_topic", "/vesc/left/state")
|
self.declare_parameter("left_state_topic", "/vesc/left/state")
|
||||||
self.declare_parameter("right_state_topic", "/vesc/right/state")
|
self.declare_parameter("right_state_topic", "/vesc/right/state")
|
||||||
|
|||||||
@ -2,8 +2,8 @@ vesc_can_driver:
|
|||||||
ros__parameters:
|
ros__parameters:
|
||||||
interface: can0
|
interface: can0
|
||||||
bitrate: 500000
|
bitrate: 500000
|
||||||
left_motor_id: 61
|
left_motor_id: 56
|
||||||
right_motor_id: 79
|
right_motor_id: 68
|
||||||
wheel_separation: 0.5
|
wheel_separation: 0.5
|
||||||
wheel_radius: 0.1
|
wheel_radius: 0.1
|
||||||
max_speed: 5.0
|
max_speed: 5.0
|
||||||
|
|||||||
@ -95,8 +95,8 @@ class VescCanDriver(Node):
|
|||||||
|
|
||||||
# Declare parameters
|
# Declare parameters
|
||||||
self.declare_parameter('interface', 'can0')
|
self.declare_parameter('interface', 'can0')
|
||||||
self.declare_parameter('left_motor_id', 61)
|
self.declare_parameter('left_motor_id', 56)
|
||||||
self.declare_parameter('right_motor_id', 79)
|
self.declare_parameter('right_motor_id', 68)
|
||||||
self.declare_parameter('wheel_separation', 0.5)
|
self.declare_parameter('wheel_separation', 0.5)
|
||||||
self.declare_parameter('wheel_radius', 0.1)
|
self.declare_parameter('wheel_radius', 0.1)
|
||||||
self.declare_parameter('max_speed', 5.0)
|
self.declare_parameter('max_speed', 5.0)
|
||||||
|
|||||||
@ -7,10 +7,10 @@ vesc_telemetry:
|
|||||||
can_interface: "can0"
|
can_interface: "can0"
|
||||||
|
|
||||||
# CAN IDs assigned to each VESC in VESC Tool
|
# CAN IDs assigned to each VESC in VESC Tool
|
||||||
# Left motor VESC: ID 61 (0x3D)
|
# Left motor VESC: ID 56 (0x38)
|
||||||
# Right motor VESC: ID 79 (0x4F)
|
# Right motor VESC: ID 68 (0x44)
|
||||||
left_can_id: 61
|
left_can_id: 56
|
||||||
right_can_id: 79
|
right_can_id: 68
|
||||||
|
|
||||||
# This node's CAN ID used as sender_id in GET_VALUES requests (0-127)
|
# This node's CAN ID used as sender_id in GET_VALUES requests (0-127)
|
||||||
sender_can_id: 127
|
sender_can_id: 127
|
||||||
|
|||||||
@ -15,8 +15,8 @@ Published topics
|
|||||||
Parameters
|
Parameters
|
||||||
----------
|
----------
|
||||||
can_interface str 'can0' SocketCAN interface
|
can_interface str 'can0' SocketCAN interface
|
||||||
left_can_id int 61 CAN ID of left VESC
|
left_can_id int 56 CAN ID of left VESC
|
||||||
right_can_id int 79 CAN ID of right VESC
|
right_can_id int 68 CAN ID of right VESC
|
||||||
poll_rate_hz int 20 Publish + request rate (10-50 Hz)
|
poll_rate_hz int 20 Publish + request rate (10-50 Hz)
|
||||||
sender_can_id int 127 This node's CAN ID
|
sender_can_id int 127 This node's CAN ID
|
||||||
overcurrent_threshold_a float 60.0 Fault alert threshold (A)
|
overcurrent_threshold_a float 60.0 Fault alert threshold (A)
|
||||||
@ -62,8 +62,8 @@ class VescTelemetryNode(Node):
|
|||||||
# Parameters
|
# Parameters
|
||||||
# ----------------------------------------------------------------
|
# ----------------------------------------------------------------
|
||||||
self.declare_parameter("can_interface", "can0")
|
self.declare_parameter("can_interface", "can0")
|
||||||
self.declare_parameter("left_can_id", 61)
|
self.declare_parameter("left_can_id", 56)
|
||||||
self.declare_parameter("right_can_id", 79)
|
self.declare_parameter("right_can_id", 68)
|
||||||
self.declare_parameter("poll_rate_hz", 20)
|
self.declare_parameter("poll_rate_hz", 20)
|
||||||
self.declare_parameter("sender_can_id", 127)
|
self.declare_parameter("sender_can_id", 127)
|
||||||
self.declare_parameter("overcurrent_threshold_a", 60.0)
|
self.declare_parameter("overcurrent_threshold_a", 60.0)
|
||||||
|
|||||||
@ -141,29 +141,29 @@ class TestParseStatus5:
|
|||||||
|
|
||||||
class TestMakeGetValuesRequest:
|
class TestMakeGetValuesRequest:
|
||||||
def test_arb_id_encodes_packet_type_and_target(self):
|
def test_arb_id_encodes_packet_type_and_target(self):
|
||||||
arb_id, payload = make_get_values_request(sender_id=127, target_id=61)
|
arb_id, payload = make_get_values_request(sender_id=127, target_id=56)
|
||||||
expected_arb = (CAN_PACKET_PROCESS_SHORT_BUFFER << 8) | 61
|
expected_arb = (CAN_PACKET_PROCESS_SHORT_BUFFER << 8) | 56
|
||||||
assert arb_id == expected_arb
|
assert arb_id == expected_arb
|
||||||
|
|
||||||
def test_payload_contains_sender_command(self):
|
def test_payload_contains_sender_command(self):
|
||||||
_, payload = make_get_values_request(sender_id=127, target_id=61)
|
_, payload = make_get_values_request(sender_id=127, target_id=56)
|
||||||
assert len(payload) == 3
|
assert len(payload) == 3
|
||||||
assert payload[0] == 127 # sender_id
|
assert payload[0] == 127 # sender_id
|
||||||
assert payload[1] == 0x00 # send_mode
|
assert payload[1] == 0x00 # send_mode
|
||||||
assert payload[2] == COMM_GET_VALUES
|
assert payload[2] == COMM_GET_VALUES
|
||||||
|
|
||||||
def test_right_vesc(self):
|
def test_right_vesc(self):
|
||||||
arb_id, payload = make_get_values_request(sender_id=127, target_id=79)
|
arb_id, payload = make_get_values_request(sender_id=127, target_id=68)
|
||||||
assert (arb_id & 0xFF) == 79
|
assert (arb_id & 0xFF) == 68
|
||||||
assert payload[2] == COMM_GET_VALUES
|
assert payload[2] == COMM_GET_VALUES
|
||||||
|
|
||||||
def test_sender_id_in_payload(self):
|
def test_sender_id_in_payload(self):
|
||||||
_, payload = make_get_values_request(sender_id=42, target_id=61)
|
_, payload = make_get_values_request(sender_id=42, target_id=56)
|
||||||
assert payload[0] == 42
|
assert payload[0] == 42
|
||||||
|
|
||||||
def test_arb_id_is_extended(self):
|
def test_arb_id_is_extended(self):
|
||||||
# Extended IDs can exceed 0x7FF (11-bit limit)
|
# Extended IDs can exceed 0x7FF (11-bit limit)
|
||||||
arb_id, _ = make_get_values_request(127, 61)
|
arb_id, _ = make_get_values_request(127, 56)
|
||||||
assert arb_id > 0x7FF
|
assert arb_id > 0x7FF
|
||||||
|
|
||||||
|
|
||||||
@ -173,7 +173,7 @@ class TestMakeGetValuesRequest:
|
|||||||
|
|
||||||
class TestVescState:
|
class TestVescState:
|
||||||
def test_defaults(self):
|
def test_defaults(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
assert s.rpm == 0
|
assert s.rpm == 0
|
||||||
assert s.current_a == pytest.approx(0.0)
|
assert s.current_a == pytest.approx(0.0)
|
||||||
assert s.voltage_v == pytest.approx(0.0)
|
assert s.voltage_v == pytest.approx(0.0)
|
||||||
@ -181,42 +181,42 @@ class TestVescState:
|
|||||||
assert s.has_fault is False
|
assert s.has_fault is False
|
||||||
|
|
||||||
def test_is_alive_fresh(self):
|
def test_is_alive_fresh(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.last_status_ts = time.monotonic()
|
s.last_status_ts = time.monotonic()
|
||||||
assert s.is_alive is True
|
assert s.is_alive is True
|
||||||
|
|
||||||
def test_is_alive_stale(self):
|
def test_is_alive_stale(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.last_status_ts = time.monotonic() - 2.0 # 2 s ago > 1 s timeout
|
s.last_status_ts = time.monotonic() - 2.0 # 2 s ago > 1 s timeout
|
||||||
assert s.is_alive is False
|
assert s.is_alive is False
|
||||||
|
|
||||||
def test_is_alive_never_received(self):
|
def test_is_alive_never_received(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
# last_status_ts defaults to 0.0 — monotonic() will be >> 1 s
|
# last_status_ts defaults to 0.0 — monotonic() will be >> 1 s
|
||||||
assert s.is_alive is False
|
assert s.is_alive is False
|
||||||
|
|
||||||
def test_has_fault_true(self):
|
def test_has_fault_true(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.fault_code = FAULT_CODE_ABS_OVER_CURRENT
|
s.fault_code = FAULT_CODE_ABS_OVER_CURRENT
|
||||||
assert s.has_fault is True
|
assert s.has_fault is True
|
||||||
|
|
||||||
def test_has_fault_false_on_none(self):
|
def test_has_fault_false_on_none(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.fault_code = FAULT_CODE_NONE
|
s.fault_code = FAULT_CODE_NONE
|
||||||
assert s.has_fault is False
|
assert s.has_fault is False
|
||||||
|
|
||||||
def test_fault_name_known(self):
|
def test_fault_name_known(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.fault_code = FAULT_CODE_OVER_TEMP_FET
|
s.fault_code = FAULT_CODE_OVER_TEMP_FET
|
||||||
assert s.fault_name == "OVER_TEMP_FET"
|
assert s.fault_name == "OVER_TEMP_FET"
|
||||||
|
|
||||||
def test_fault_name_unknown(self):
|
def test_fault_name_unknown(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
s.fault_code = 99
|
s.fault_code = 99
|
||||||
assert "UNKNOWN" in s.fault_name
|
assert "UNKNOWN" in s.fault_name
|
||||||
|
|
||||||
def test_fault_name_none(self):
|
def test_fault_name_none(self):
|
||||||
s = VescState(can_id=61)
|
s = VescState(can_id=56)
|
||||||
assert s.fault_name == "NONE"
|
assert s.fault_name == "NONE"
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user