Skip to content

Commit 23dbc48

Browse files
committed
fix(motor test): use png files in motor diagrams
1 parent 6237038 commit 23dbc48

File tree

4 files changed

+153
-222
lines changed

4 files changed

+153
-222
lines changed

ardupilot_methodic_configurator/backend_filesystem_program_settings.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -343,14 +343,14 @@ def set_setting(setting: str, value: Union[bool, str, float]) -> None:
343343
@staticmethod
344344
def motor_diagram_filepath(frame_class: int, frame_type: int) -> tuple[str, str]:
345345
"""
346-
Get the filepath for the motor diagram SVG file.
346+
Get the filepath for the motor diagram PNG file.
347347
348348
Args:
349349
frame_class: ArduPilot frame class (1=QUAD, 2=HEXA, etc.)
350350
frame_type: ArduPilot frame type (0=PLUS, 1=X, etc.)
351351
352352
Returns:
353-
str: Absolute path to the motor diagram SVG file
353+
str: Absolute path to the motor diagram PNG file
354354
str: Error message if multiple or no files found, empty string if no error
355355
356356
"""
@@ -363,12 +363,12 @@ def motor_diagram_filepath(frame_class: int, frame_type: int) -> tuple[str, str]
363363
# Running as script
364364
application_path = os_path.dirname(os_path.dirname(os_path.abspath(__file__)))
365365

366-
images_dir = os_path.join(application_path, "ardupilot_methodic_configurator", "images")
366+
images_dir = os_path.join(application_path, "ardupilot_methodic_configurator", "images", "motor_diagrams_png")
367367

368-
# Generate SVG filename based on frame configuration
369-
filename = f"m_{frame_class:02d}_{frame_type:02d}_*.svg"
368+
# Generate PNG filename based on frame configuration
369+
filename = f"m_{frame_class:02d}_{frame_type:02d}_*.png"
370370

371-
# Search for matching SVG file (since exact naming varies)
371+
# Search for matching PNG file (since exact naming varies)
372372
matching_files = glob.glob(os_path.join(images_dir, filename))
373373

374374
err_msg = (

ardupilot_methodic_configurator/data_model_motor_test.py

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1023,30 +1023,6 @@ def update_frame_type_from_selection(
10231023
logging_error(error_msg)
10241024
raise FrameConfigurationError(error_msg) from e
10251025

1026-
def get_svg_scaling_info(
1027-
self, canvas_width: int, canvas_height: int, svg_width: int, svg_height: int
1028-
) -> tuple[float, int]:
1029-
"""
1030-
Calculate SVG scaling information for diagram display.
1031-
1032-
Args:
1033-
canvas_width: Canvas width in pixels
1034-
canvas_height: Canvas height in pixels
1035-
svg_width: SVG width in pixels
1036-
svg_height: SVG height in pixels
1037-
1038-
Returns:
1039-
tuple[float, int]: (scale_factor, scaled_height)
1040-
1041-
"""
1042-
if svg_width > 0 and svg_height > 0:
1043-
scale_x = canvas_width / svg_width
1044-
scale_y = canvas_height / svg_height
1045-
scale = min(scale_x, scale_y) * 0.9 # Leave some margin
1046-
scaled_height = int(svg_height * scale)
1047-
return scale, scaled_height
1048-
return 1.0, svg_height
1049-
10501026
def get_battery_status_color(self) -> str:
10511027
"""
10521028
Get the appropriate color for battery voltage display.

ardupilot_methodic_configurator/frontend_tkinter_motor_test.py

Lines changed: 66 additions & 142 deletions
Original file line numberDiff line numberDiff line change
@@ -31,15 +31,6 @@
3131
from tkinter.simpledialog import askfloat
3232
from typing import Callable, Union
3333

34-
try:
35-
import tksvg
36-
except ImportError:
37-
tksvg = None
38-
39-
# For fallback SVG rendering
40-
import io
41-
42-
import cairosvg
4334
from PIL import Image, ImageTk
4435

4536
from ardupilot_methodic_configurator import _
@@ -90,11 +81,10 @@ def __init__(
9081
self.diagram_canvas: Canvas
9182
self.batt_voltage_label: ttk.Label
9283
self.batt_current_label: ttk.Label
93-
self._current_svg_image = None # Store SVG image reference
84+
self._current_svg_image: Union[ImageTk.PhotoImage, None] = None # Store image reference (PNG or other format)
9485
self._first_motor_test = True # Track if this is the first motor test
9586
self._frame_options_loaded = False # Track if frame options have been loaded
96-
self._diagram_loaded = False # Track if diagram has been loaded initially
97-
self._diagrams_path = ""
87+
self._diagrams_path = "" # Cache diagram path for performance
9888
self._content_frame = None # Store reference to content frame for widget searches
9989

10090
self._create_widgets()
@@ -142,28 +132,11 @@ def _create_widgets(self) -> None:
142132
self.frame_type_combobox.pack(side="left", padx=5, expand=True, fill="x")
143133
self.frame_type_combobox.bind("<<ComboboxSelected>>", self._on_frame_type_change)
144134

145-
self.diagram_canvas = Canvas(config_frame, width=400, height=300, bg="white")
135+
self.diagram_canvas = Canvas(config_frame, width=260, height=260, bg="white")
146136
self.diagram_canvas.pack()
147137

148-
# --- 2. Arm and Min Throttle Configuration ---
149-
motor_params_frame = ttk.LabelFrame(content_frame, text=_("2. Arm and Min Throttle Configuration"))
150-
motor_params_frame.pack(padx=10, pady=5, fill="x")
151-
152-
button_frame = ttk.Frame(motor_params_frame)
153-
button_frame.pack(fill="x", pady=5)
154-
ttk.Button(
155-
button_frame,
156-
text=_("Set Motor Spin Arm"),
157-
command=self._set_motor_spin_arm,
158-
).pack(side="left", padx=5)
159-
ttk.Button(
160-
button_frame,
161-
text=_("Set Motor Spin Min"),
162-
command=self._set_motor_spin_min,
163-
).pack(side="left", padx=5)
164-
165-
# --- 3. Motor Order/Direction Configuration ---
166-
testing_frame = ttk.LabelFrame(content_frame, text=_("3. Motor Order/Direction Configuration"))
138+
# --- 2. Motor Order/Direction Configuration ---
139+
testing_frame = ttk.LabelFrame(content_frame, text=_("2. Motor Order/Direction Configuration"))
167140
testing_frame.pack(padx=10, pady=5, fill="x")
168141

169142
controls_frame = ttk.Frame(testing_frame)
@@ -209,6 +182,23 @@ def _create_widgets(self) -> None:
209182
).pack(side="left", padx=5)
210183
ttk.Button(test_controls_frame, text=_("Stop All Motors"), command=self._stop_all_motors).pack(side="right", padx=5)
211184

185+
# --- 3. Arm and Min Throttle Configuration ---
186+
motor_params_frame = ttk.LabelFrame(content_frame, text=_("3. Arm and Min Throttle Configuration"))
187+
motor_params_frame.pack(padx=10, pady=5, fill="x")
188+
189+
button_frame = ttk.Frame(motor_params_frame)
190+
button_frame.pack(fill="x", pady=5)
191+
ttk.Button(
192+
button_frame,
193+
text=_("Set Motor Spin Arm"),
194+
command=self._set_motor_spin_arm,
195+
).pack(side="left", padx=5)
196+
ttk.Button(
197+
button_frame,
198+
text=_("Set Motor Spin Min"),
199+
command=self._set_motor_spin_min,
200+
).pack(side="left", padx=5)
201+
212202
def _create_motor_buttons(self, parent: Union[Frame, ttk.Frame]) -> None:
213203
"""Create the motor test buttons and detection comboboxes."""
214204
motor_labels = self.model.motor_labels
@@ -255,10 +245,8 @@ def _update_view(self) -> None:
255245
self._update_frame_options()
256246
self._frame_options_loaded = True
257247

258-
# Only load diagram once during initial setup, not on every update
259-
if not self._diagram_loaded:
260-
self._update_diagram()
261-
self._diagram_loaded = True
248+
# Update diagram when needed
249+
self._update_diagram()
262250

263251
self._update_motor_buttons_layout()
264252
self._update_battery_status()
@@ -374,123 +362,56 @@ def _update_diagram(self) -> None:
374362
diagram_path, error_msg = self.model.get_motor_diagram_path()
375363
self._diagrams_path = diagram_path
376364

377-
if diagram_path and diagram_path.endswith(".svg"):
378-
logging_error(_("Found SVG diagram at: %(path)s"), {"path": diagram_path})
379-
width = 400
380-
height = 300
365+
if diagram_path and diagram_path.endswith(".png"):
366+
logging_debug(_("Found PNG diagram at: %(path)s"), {"path": diagram_path})
367+
width = 250
368+
height = 250
381369
canvas_width = int(self.diagram_canvas.winfo_width() or width)
382370
canvas_height = int(self.diagram_canvas.winfo_height() or height)
383371
if canvas_width <= 0:
384372
canvas_width = max(1, int(width))
385373
if canvas_height <= 0:
386374
canvas_height = max(1, int(height))
375+
387376
try:
388-
if tksvg is not None:
389-
# Use tksvg to render SVG
390-
svg_image = tksvg.SvgImage(file=diagram_path)
391-
# Scale the image to fit the canvas
392-
393-
# Calculate scaling to fit within canvas while maintaining aspect ratio
394-
svg_width = svg_image.width()
395-
svg_height = svg_image.height()
396-
_scale, scaled_height = self.model.get_svg_scaling_info(
397-
canvas_width, canvas_height, svg_width, svg_height
377+
# Load and display PNG image using PIL
378+
image = Image.open(diagram_path)
379+
380+
# Calculate scaling to fit within canvas while maintaining aspect ratio
381+
img_width, img_height = image.size
382+
if img_width > 0 and img_height > 0:
383+
# Calculate scale factor to fit image in canvas
384+
scale_x = canvas_width / img_width
385+
scale_y = canvas_height / img_height
386+
scale = min(scale_x, scale_y)
387+
388+
# Make image 30% smaller (multiply by 0.7)
389+
scale *= 0.7
390+
391+
# Calculate new dimensions
392+
new_width = int(img_width * scale)
393+
new_height = int(img_height * scale)
394+
395+
# Resize image
396+
resized_image = image.resize((new_width, new_height), Image.Resampling.LANCZOS)
397+
tk_image = ImageTk.PhotoImage(resized_image)
398+
399+
# Center the image on the canvas
400+
self.diagram_canvas.create_image(
401+
canvas_width // 2, canvas_height // 2, image=tk_image, anchor="center"
398402
)
399-
400-
if svg_width > 0 and svg_height > 0:
401-
# Create scaled image
402-
scaled_svg = tksvg.SvgImage(file=diagram_path, scaletoheight=scaled_height)
403-
self.diagram_canvas.create_image(
404-
canvas_width // 2, canvas_height // 2, image=scaled_svg, anchor="center"
405-
)
406-
# Keep a reference to prevent garbage collection
407-
# Store in the view instance instead of canvas
408-
self._current_svg_image = scaled_svg
409-
else:
410-
self.diagram_canvas.create_text(200, 150, text=_("Invalid SVG diagram"), fill="red")
411-
elif cairosvg is not None:
412-
# Use cairosvg to rasterize the SVG to PNG and display via PIL on the canvas.
413-
414-
try:
415-
png_data = cairosvg.svg2png(
416-
url=str(diagram_path), # output_width=canvas_width, output_height=canvas_height
417-
)
418-
# Defensive check: svg2png should return bytes; if not, log and fallback
419-
if not isinstance(png_data, (bytes, bytearray)):
420-
logging_error(
421-
_("cairosvg.svg2png returned unexpected type: %(type)s"),
422-
{"type": type(png_data)},
423-
)
424-
self.diagram_canvas.create_text(
425-
canvas_width // 2,
426-
canvas_height // 2,
427-
text=_("SVG render returned unexpected data type for %(path)s") % {"path": diagram_path},
428-
fill="red",
429-
width=380,
430-
)
431-
raise TypeError("svg2png returned non-bytes data")
432-
433-
try:
434-
image = Image.open(io.BytesIO(png_data))
435-
except TypeError as img_e:
436-
# Image.open failed due to bad argument type - log details
437-
logging_error(
438-
_("PIL.Image.open TypeError: %(error)s - png_data type: %(type)s"),
439-
{"error": img_e, "type": type(png_data)},
440-
)
441-
self.diagram_canvas.create_text(
442-
canvas_width // 2,
443-
canvas_height // 2,
444-
text=_("Error opening rendered PNG for %(path)s") % {"path": diagram_path},
445-
fill="red",
446-
width=380,
447-
)
448-
raise
449-
450-
tk_image = ImageTk.PhotoImage(image)
451-
# Center the image on the canvas
452-
self.diagram_canvas.create_image(
453-
canvas_width // 2,
454-
canvas_height // 2,
455-
image=tk_image,
456-
anchor="center",
457-
)
458-
# Keep reference to avoid garbage collection
459-
self._current_svg_image = tk_image
460-
except TypeError as e:
461-
logging_error(_("TypeError rendering SVG with cairosvg: %(error)s"), {"error": e})
462-
self.diagram_canvas.create_text(
463-
canvas_width // 2,
464-
canvas_height // 2,
465-
text=_("TypeError rendering SVG: %(path)s") % {"path": diagram_path},
466-
fill="red",
467-
width=380,
468-
)
469-
except Exception as e: # pylint: disable=broad-exception-caught
470-
logging_error(_("Error rendering SVG with cairosvg: %(error)s"), {"error": e})
471-
# Show an informative fallback message
472-
self.diagram_canvas.create_text(
473-
canvas_width // 2,
474-
canvas_height // 2,
475-
text=_("Error rendering SVG: %(path)s") % {"path": diagram_path},
476-
fill="red",
477-
width=380,
478-
)
403+
# Keep a reference to prevent garbage collection
404+
self._current_svg_image = tk_image
479405
else:
480-
# No SVG rendering backend available, show filename instead
481-
self.diagram_canvas.create_text(
482-
canvas_width // 2,
483-
canvas_height // 2,
484-
text=_("SVG diagram: %(path)s") % {"path": diagram_path},
485-
fill="black",
486-
width=380,
487-
)
406+
self.diagram_canvas.create_text(200, 150, text=_("Invalid PNG diagram"), fill="red")
407+
488408
except Exception as e: # pylint: disable=broad-exception-caught
489-
logging_error(_("Error loading SVG diagram: %(error)s"), {"error": e})
409+
logging_error(_("Error loading PNG diagram: %(error)s"), {"error": e})
490410
self.diagram_canvas.create_text(200, 150, text=_("Error loading diagram"), fill="red")
491411
else:
492412
# Fallback: just show the path
493-
logging_error(error_msg)
413+
if error_msg:
414+
logging_error(error_msg)
494415
self.diagram_canvas.create_text(
495416
200, 150, text=_("Diagram: %(path)s") % {"path": diagram_path}, fill="black", width=380
496417
)
@@ -530,6 +451,9 @@ def _on_frame_type_change(self, _event: object) -> None:
530451
reset_progress_window.destroy() # for the case that we are doing a test and there is no real FC connected
531452
connection_progress_window.destroy() # for the case that we are doing a test and there is no real FC connected
532453

454+
# Invalidate diagram cache since frame type changed
455+
self._diagrams_path = ""
456+
533457
# Update UI components
534458
self._update_motor_buttons_layout()
535459
self._update_diagram()
@@ -591,7 +515,7 @@ def _set_motor_spin_arm(self) -> None:
591515
current_val = self.model.get_parameter("MOT_SPIN_ARM")
592516
new_val = askfloat(
593517
_("Set Motor Spin Arm"),
594-
_("Enter new value for MOT_SPIN_ARM:"),
518+
_("Enter new value for MOT_SPIN_ARM with 0.02 margin:"),
595519
initialvalue=current_val,
596520
)
597521
if new_val is not None:
@@ -609,7 +533,7 @@ def _set_motor_spin_min(self) -> None:
609533
current_val = self.model.get_parameter("MOT_SPIN_MIN")
610534
new_val = askfloat(
611535
_("Set Motor Spin Min"),
612-
_("Enter new value for MOT_SPIN_MIN:"),
536+
_("Enter new value for MOT_SPIN_MIN, must be at least 0.02 higher than MOT_SPIN_ARM:"),
613537
initialvalue=current_val,
614538
minvalue=0.0,
615539
maxvalue=1.0,

0 commit comments

Comments
 (0)