diff --git a/safety_user_plugin/scripts/qt_wrapper.py b/safety_user_plugin/scripts/qt_wrapper.py
index cc84a8d..9dda2cf 100644
--- a/safety_user_plugin/scripts/qt_wrapper.py
+++ b/safety_user_plugin/scripts/qt_wrapper.py
@@ -93,7 +93,7 @@ class QtWrapper:
def update_selected_robot_info(self,robot_info):
linear_vel = math.sqrt(robot_info.linear_velocity[0]**2 + robot_info.linear_velocity[1]**2)
- self.widget.idLabel.setText('PIONIER' + str(robot_id))
+ self.widget.idLabel.setText('PIONIER' + str(robot_info.robot_id))
self.widget.batteryLabel.setText("{:.2f}".format(robot_info.battery_voltage))
self.widget.linearLabel.setText("{:.2f}".format(linear_vel))
self.widget.angularLabel.setText("{:.2f}".format(robot_info.angular_velocity[2]))
diff --git a/safety_user_plugin/scripts/ros_wrapper.py b/safety_user_plugin/scripts/ros_wrapper.py
index 989c0a0..fc86415 100644
--- a/safety_user_plugin/scripts/ros_wrapper.py
+++ b/safety_user_plugin/scripts/ros_wrapper.py
@@ -155,7 +155,8 @@ class ROSWrapper:
# Restarting connection timer to avoid raising robot_connection_lost_callback
self.restart_connection_timer()
- _robot_info = RobotInfo(0).update_robot_info(msg)
+ _robot_info = RobotInfo(0)
+ _robot_info.update_robot_info(msg)
self.selected_robot_info_update_callback(_robot_info)
def handle_master_stop_update(self,msg):
diff --git a/safety_user_plugin/scripts/user_info.py b/safety_user_plugin/scripts/user_info.py
index bf0ed6a..cb81450 100644
--- a/safety_user_plugin/scripts/user_info.py
+++ b/safety_user_plugin/scripts/user_info.py
@@ -21,7 +21,12 @@ class UserInfo:
self.robots_id_list = robots_id_list
def update_selected_robot_info(self,new_robot_info):
- raise NotImplementedError
+ self.selected_robot.robot_id = new_robot_info.robot_id
+ self.selected_robot.battery_voltage = new_robot_info.battery_voltage
+ self.selected_robot.linear_velocity = new_robot_info.linear_velocity
+ self.selected_robot.angular_velocity = new_robot_info.angular_velocity
+ self.selected_robot.state = new_robot_info.state
+ self.selected_robot.clutch = new_robot_info.clutch
def get_user_stop_state(self):
return self.user_stop_state
diff --git a/safety_user_plugin/ui/user_view.ui b/safety_user_plugin/ui/user_view.ui
index f71d8ed..5dde685 100644
--- a/safety_user_plugin/ui/user_view.ui
+++ b/safety_user_plugin/ui/user_view.ui
@@ -130,6 +130,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+
-
@@ -137,6 +140,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+
-
@@ -144,6 +150,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+
-
@@ -151,6 +160,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+
-
@@ -158,6 +170,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+
-
@@ -165,6 +180,9 @@
<html><head/><body><p align="center">-</p></body></html>
+
+ Qt::AlignCenter
+