-
Notifications
You must be signed in to change notification settings - Fork 364
feat(rqt): Add update rate and async info to details window #2510
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
base: master
Are you sure you want to change the base?
Changes from all commits
35a2323
b61236d
bda5c2c
086847b
ee2dcc5
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -285,7 +285,47 @@ def _on_ctrl_info(self, index): | |||||||||||||||
ctrl = self._controllers[index.row()] | ||||||||||||||||
popup.ctrl_name.setText(ctrl.name) | ||||||||||||||||
popup.ctrl_type.setText(ctrl.type) | ||||||||||||||||
|
||||||||||||||||
|
||||||||||||||||
#Fetch the update_rate and is_async | ||||||||||||||||
update_rate = "N/A" | ||||||||||||||||
is_async = "N/A" # Default to N/A for now | ||||||||||||||||
|
||||||||||||||||
try: | ||||||||||||||||
# --- Check for per-controller params first --- | ||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||||||||||
param_names = [f"{ctrl.name}.update_rate", f"{ctrl.name}.is_async"] | ||||||||||||||||
response = call_get_parameters( | ||||||||||||||||
node=self._node, node_name=self._cm_name, parameter_names=param_names) | ||||||||||||||||
|
||||||||||||||||
# Check the response for valid types | ||||||||||||||||
# In Rolling, INTEGER is type 2, BOOL is type 1, NOT_SET is 0 | ||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||||||||||
if response.values[0].type == 2: # Found per-controller update_rate | ||||||||||||||||
update_rate = f"{response.values[0].integer_value} Hz" | ||||||||||||||||
if response.values[1].type == 1: # Found per-controller is_async | ||||||||||||||||
is_async = str(response.values[1].bool_value) | ||||||||||||||||
|
||||||||||||||||
# --- If per-controller update_rate not found, check global --- | ||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||||||||||
if update_rate == "N/A": | ||||||||||||||||
response_global = call_get_parameters( | ||||||||||||||||
node=self._node, node_name=self._cm_name, parameter_names=['update_rate']) | ||||||||||||||||
# Check for a valid response and correct type (INTEGER = 2) | ||||||||||||||||
if response_global.values and response_global.values[0].type == 2: | ||||||||||||||||
update_rate = f"{response_global.values[0].integer_value} Hz (Global)" | ||||||||||||||||
|
||||||||||||||||
# --- Set a default for is_async if not found --- | ||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||||||||||
if is_async == "N/A": | ||||||||||||||||
is_async = "False (Default)" | ||||||||||||||||
|
||||||||||||||||
except Exception as e: | ||||||||||||||||
# Use the correct '.warning()' method and no exc_info | ||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
? |
||||||||||||||||
self._node.get_logger().warning( | ||||||||||||||||
f"Could not get some parameters for controller {ctrl.name}: {e}") | ||||||||||||||||
|
||||||||||||||||
# Update the labels you created in the .ui file | ||||||||||||||||
popup.label_update_rate_value.setText(update_rate) | ||||||||||||||||
popup.label_async_setting_value.setText(is_async) | ||||||||||||||||
|
||||||||||||||||
|
||||||||||||||||
Comment on lines
+323
to
+327
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. sounds like some LLM description ;)
Suggested change
|
||||||||||||||||
|
||||||||||||||||
res_model = QStandardItemModel() | ||||||||||||||||
model_root = QStandardItem("Claimed Interfaces") | ||||||||||||||||
res_model.appendRow(model_root) | ||||||||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.