Skip to content
Open
Show file tree
Hide file tree
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
40 changes: 40 additions & 0 deletions rqt_controller_manager/resource/popup_info.ui
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,46 @@
<enum>Qt::PlainText</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_update_rate">
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;Update Rate:&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="textFormat">
<enum>Qt::RichText</enum>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="label_update_rate_value">
<property name="text">
<string>N/A</string>
</property>
<property name="textFormat">
<enum>Qt::PlainText</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_async_setting">
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;Async Setting:&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="textFormat">
<enum>Qt::RichText</enum>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="label_async_setting_value">
<property name="text">
<string>N/A</string>
</property>
<property name="textFormat">
<enum>Qt::PlainText</enum>
</property>
</widget>
</item>
</layout>
</item>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#Fetch the update_rate and is_async
# 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 ---
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# --- Check for per-controller params first ---
# Check for per-controller params first

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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# In Rolling, INTEGER is type 2, BOOL is type 1, NOT_SET is 0
# INTEGER is type 2, BOOL is type 1, NOT_SET is 0

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 ---
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# --- If per-controller update_rate not found, check global ---
# If per-controller update_rate not found, check global

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 ---
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# --- Set a default for is_async if not found ---
# Set a default for is_async if not found

if is_async == "N/A":
is_async = "False (Default)"

except Exception as e:
# Use the correct '.warning()' method and no exc_info
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# Use the correct '.warning()' method and no exc_info

?

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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sounds like some LLM description ;)

Suggested change
# 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)
popup.label_update_rate_value.setText(update_rate)
popup.label_async_setting_value.setText(is_async)


res_model = QStandardItemModel()
model_root = QStandardItem("Claimed Interfaces")
res_model.appendRow(model_root)
Expand Down
Loading