sr_data_visualizer_gui.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright 2020 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 import yaml
18 import matplotlib
19 import numpy as np
20 import os
21 import signal
22 import rospy
23 import rospkg
24 import string
25 import re
26 import time
27 import atexit
28 matplotlib.use("Qt5Agg") # noqa
29 from python_qt_binding.QtGui import *
30 from python_qt_binding.QtCore import *
31 try:
32  from python_qt_binding.QtWidgets import *
33 except ImportError:
34  pass
35 import sys
36 from matplotlib.backends.backend_qt5agg import FigureCanvasQTAgg as FigureCanvas
37 from matplotlib.figure import Figure
38 from matplotlib.animation import TimedAnimation
39 from matplotlib.lines import Line2D
40 from python_qt_binding.QtGui import *
41 from python_qt_binding.QtCore import *
42 from qt_gui.plugin import Plugin
43 from python_qt_binding import loadUi
44 try:
45  from python_qt_binding.QtWidgets import *
46 except ImportError:
47  pass
48 from sensor_msgs.msg import JointState
49 from control_msgs.msg import JointControllerState
50 from diagnostic_msgs.msg import DiagnosticArray
51 from std_msgs.msg import Float64MultiArray
52 from QtGui import QIcon, QColor, QPainter, QFont
53 from QtWidgets import QMessageBox, QWidget
54 from QtCore import QRectF, QTimer
55 from sr_robot_msgs.msg import Biotac, BiotacAll
56 from sr_utilities.hand_finder import HandFinder
57 
58 
60  def __init__(self, context):
61  self.init_complete = False
62  self.first_run = True
63  super(SrDataVisualizer, self).__init__(context)
64  self.setObjectName("SrDataVisualizer")
65  self._widget = QWidget()
66  self._hand_finder = HandFinder()
67  self._hand_parameters = self._hand_finder.get_hand_parameters()
68  self._joint_prefix = next(iter(self._hand_parameters.joint_prefix.values()))
69  self._hand_g = False
70  for hand, joints in self._hand_finder.hand_joints.items():
71  if self._joint_prefix + 'WRJ1' not in joints:
72  self._hand_g = True
73  for key in self._hand_parameters.joint_prefix:
74  self.hand_serial = key
75  self._joint_prefix = self._hand_parameters.joint_prefix[self.hand_serial]
76  ui_file = os.path.join(rospkg.RosPack().get_path('sr_data_visualization'), 'uis', 'hand-e_visualizer.ui')
77  loadUi(ui_file, self._widget)
78  if __name__ != "__main__":
79  context.add_widget(self._widget)
80  self._widget.setWindowTitle("Dexterous Hand Data Visualizer")
81 
82  # Set white background color
83  p = self._widget.palette()
84  p.setColor(self._widget.backgroundRole(), Qt.white)
85  self._widget.setPalette(p)
86  self.tab_widget_main = self._widget.findChild(QTabWidget, "tabWidget_main")
87  self.tabWidget_motor_stats = self._widget.findChild(QTabWidget, "tabWidget_motor_stats")
88 
89  # Change tabs background color
90  p = self.tab_widget_main.palette()
91  stylesheet = """
92  QTabWidget>QWidget>QWidget{background: white;}
93  """
94  p.setColor(self.tab_widget_main.backgroundRole(), Qt.white)
95  self.tab_widget_main.setStyleSheet(stylesheet)
96 
97  self.tab_widget_main.currentChanged.connect(self.tab_change)
98  self.tabWidget_motor_stats.currentChanged.connect(self.tab_change_mstat)
99 
100  motor_stat_keys_file = os.path.join(rospkg.RosPack().get_path('sr_data_visualization'), 'config',
101  'data_visualiser_motor_stat_keys.yaml')
102  if self._hand_g:
103  parameters_file = os.path.join(rospkg.RosPack().get_path('sr_data_visualization'), 'config',
104  'data_visualiser_parameters_rh_lite.yaml')
105  elif self._joint_prefix == "rh_":
106  parameters_file = os.path.join(rospkg.RosPack().get_path('sr_data_visualization'), 'config',
107  'data_visualiser_parameters_rh.yaml')
108  elif self._joint_prefix == "lh_":
109  parameters_file = os.path.join(rospkg.RosPack().get_path('sr_data_visualization'), 'config',
110  'data_visualiser_parameters_lh.yaml')
111  else:
112  rospy.logerr("Unknown hand detected")
113 
114  self.t0 = time.time()
115 
116  self.reset_tab_1 = self._widget.findChild(QPushButton, "reset_tab1")
117  self.reset_tab_2 = self._widget.findChild(QPushButton, "reset_tab2")
118  self.reset_tab_3 = self._widget.findChild(QPushButton, "reset_tab3")
119  self.reset_tab_1.clicked.connect(self.reset_1)
120  self.reset_tab_2.clicked.connect(self.reset_2)
121  self.reset_tab_3.clicked.connect(self.reset_3)
122 
123  self.font_offset = -3
124 
125  self._widget.resizeEvent = self.on_resize_main
126 
127  self.type_dict = {
128  0: "pos_vel_eff",
129  1: "control_loops",
130  2: "motor_stat"
131  }
132 
135 
136  with open(motor_stat_keys_file, 'r') as stream:
137  try:
138  self.motor_stat_keys = yaml.load(stream)
139  except yaml.YAMLError as exc:
140  print(exc)
141 
142  with open(parameters_file, 'r') as stream:
143  try:
144  data_loaded = yaml.load(stream)
145  self._initialize(data_loaded)
146  except yaml.YAMLError as exc:
147  print(exc)
148 
149  self._setup_radio_buttons()
150 
151  self.tabWidget_motor_stats.setCurrentIndex(0)
152  self.tabWidget_motor_stats.setCurrentIndex(1)
153  self.tabWidget_motor_stats.setCurrentIndex(2)
154  self.tabWidget_motor_stats.setCurrentIndex(3)
155  self.tabWidget_motor_stats.setCurrentIndex(4)
156  self.tabWidget_motor_stats.setCurrentIndex(5)
157  self.tabWidget_motor_stats.setCurrentIndex(0)
158 
159  # Update legends on motor_stat graphs
160  self._change_graphs(all=True, type=2, ncol=1)
161 
162  QTimer.singleShot(5000, self.reset_1)
163  self.init_complete = True
164 
165  def shutdown_plugin(self):
166  graph_type = [key for key, value in self.graph_names_global.items()]
167  for element in graph_type:
168  for key, graph in self.graph_dict_global[element].iteritems():
169  graph.enabled = False
170  self.init_complete = False
171 
172  def on_resize_main(self, empty):
173  if (self._widget.width() * self._widget.height()) < 3500000:
174  self.font_offset = -3
175  else:
176  self.font_offset = 1
177 
178  def reset_1(self):
179  self._reset_graphs(0)
180  self.radio_button_all.setChecked(True)
181 
182  def reset_2(self):
183  self._reset_graphs(1)
184  self.radio_button_ctrl_all.setChecked(True)
185 
186  def reset_3(self):
187  self._reset_graphs(2)
188  self.radioButton_all_motor_stat.setChecked(True)
189 
190  def _reset_graphs(self, tab):
191  graph_type = [key for key, value in self.graph_names_global.items() if self.type_dict[tab] in key]
192  for element in graph_type:
193  for key, graph in self.graph_dict_global[element].iteritems():
194  graph.ax1.clear()
195  graph._handle_resize()
196  if tab == 2:
197  ncol = 1
198  else:
199  ncol = 3
200  self._change_graphs(all=True, type=tab, ncol=ncol)
201 
204  self.timer = QTimer(self._widget)
205  for i in range(self.number_of_biotacs):
206  tactile_gui = SrGuiBiotac(None)
207  tactile_gui._widget = self._widget
208  tactile_gui.find_children(i)
209  self.tactile_gui_list.append(tactile_gui)
210  widget = self._widget.findChild(QWidget, "widget" + "_" + str(i))
211  widget.resizeEvent = self.on_resize_tactile
212 
213  self.timer.timeout.connect(widget.update)
214  widget.paintEvent = tactile_gui.paintEvent
215  if not tactile_gui._hand_parameters.mapping:
216  rospy.logerr("No hand detected")
217 
218  self.label_list = []
219  self.lcd_list = []
220 
221  for j in range(self.number_of_biotacs):
222  lcds = []
223  labels = []
224  for i in range(1, self.electrodes_per_biotac):
225  if i < 10:
226  lcd = self._widget.findChild(QLCDNumber, "lcdE0" + str(i) + "_" + str(j))
227  label = self._widget.findChild(QLabel, "label_E0" + str(i) + "_" + str(j))
228  else:
229  lcd = self._widget.findChild(QLCDNumber, "lcdE" + str(i) + "_" + str(j))
230  label = self._widget.findChild(QLabel, "label_E" + str(i) + "_" + str(j))
231  lcds.append(lcd)
232  labels.append(label)
233  self.lcd_list.append(lcds)
234  self.label_list.append(labels)
235  self.timer.start(50)
236 
237  def on_resize_tactile(self, none):
238  for tactile_widget in self.tactile_gui_list:
239  tactile_widget.redraw_electrodes()
240 
241  if (self._widget.width() * self._widget.height()) < 3500000:
242  scale = 6
243  mheight = 18
244  else:
245  scale = 12
246  mheight = 30
247 
248  font = QFont('Sans Serif', scale)
249  font.setKerning(True)
250  for j in range(self.number_of_biotacs):
251  for i in range(self.electrodes_per_biotac - 1):
252  self.lcd_list[j][i].setMinimumHeight(2)
253  self.lcd_list[j][i].setMaximumHeight(mheight)
254  self.label_list[j][i].setFont(font)
255 
256  def tab_change_mstat(self, tab_index):
257  self._hide_and_refresh(tab_index, "motor_stat")
258 
259  def tab_change(self, tab_index):
260  self._hide_and_refresh(tab_index, "main")
261 
262  def _hide_and_refresh(self, tab_index, tab_type):
263  self._hide_tabs(tab_index, tab_type)
264 
265  def _hide_tabs(self, tab_index, tab):
266  if tab == "main":
267  if tab_index == 0:
268  graph_type = [key for key, value in self.graph_names_global.items() if "pos_vel_eff" not in key]
269  self._disable_graphs(graph_type, disable=True)
270  self._disable_graphs(["pos_vel_eff"], disable=False)
271  elif tab_index == 1:
272  graph_type = [key for key, value in self.graph_names_global.items() if "control_loops" not in key]
273  self._disable_graphs(graph_type, disable=True)
274  self._disable_graphs(["control_loops"], disable=False)
275  elif tab_index == 2:
276  graph_type = [key for key, value in self.graph_names_global.items() if "motor_stat" not in key]
277  self._disable_graphs(graph_type, disable=True)
279  elif tab_index == 3:
280  graph_type = [key for key, value in self.graph_names_global.items() if "palm_extras" not in key]
281  self._disable_graphs(graph_type, disable=True)
282  graph_type = [key for key, value in self.graph_names_global.items() if "palm_extras" in key]
283  self._disable_graphs(graph_type, disable=False)
284  elif tab_index == 4:
285  graph_type = [key for key, value in self.graph_names_global.items() if "biotacs" not in key]
286  self._disable_graphs(graph_type, disable=True)
287  self._disable_graphs(["biotacs"], disable=False)
288  elif tab_index == 5:
289  graph_type = [key for key, value in self.graph_names_global.items()]
290  self._disable_graphs(graph_type, disable=True)
291  elif tab == "motor_stat":
293 
295  tab_index = self.tabWidget_motor_stats.currentIndex()
296  tab_index_dict = {
297  0: "thj",
298  1: "ffj",
299  2: "mfj",
300  3: "rfj",
301  4: "lfj",
302  5: "wrj"
303  }
304  self._hide_all_but(tab_index_dict[tab_index])
305 
306  def _hide_all_but(self, joint_group):
307  x = [value for key, value in self.graph_dict_global["motor_stat"].items() if joint_group in key]
308  for graph in x:
309  graph.enabled = True
310  x = [value for key, value in self.graph_dict_global["motor_stat"].items() if joint_group not in key]
311  for graph in x:
312  graph.enabled = False
313 
314  def _disable_graphs(self, graph_type, disable):
315  for element in graph_type:
316  for key, graph in self.graph_dict_global[element].iteritems():
317  graph.enabled = not disable
318 
320  self.radio_button_velocity = self._widget.findChild(QRadioButton, "radioButton_velocity")
321  self.radio_button_all = self._widget.findChild(QRadioButton, "radioButton_all")
322  self.radio_button_position = self._widget.findChild(QRadioButton, "radioButton_position")
323  self.radio_button_effort = self._widget.findChild(QRadioButton, "radioButton_effort")
324 
325  self.radio_button_setpoint = self._widget.findChild(QRadioButton, "radioButton_setpoint")
326  self.radio_button_input = self._widget.findChild(QRadioButton, "radioButton_input")
327  self.radio_button_dInput = self._widget.findChild(QRadioButton, "radioButton_dInput")
328  self.radio_button_error = self._widget.findChild(QRadioButton, "radioButton_error")
329  self.radio_button_output = self._widget.findChild(QRadioButton, "radioButton_output")
330  self.radio_button_ctrl_all = self._widget.findChild(QRadioButton, "radioButton_ctrl_all")
331 
332  self.radioButton_all_motor_stat = self._widget.findChild(QRadioButton, "radioButton_all_motor_stat")
333  self.radioButton_strain_gauge_left = self._widget.findChild(QRadioButton, "radioButton_strain_gauge_left")
334  self.radioButton_strain_gauge_right = self._widget.findChild(QRadioButton, "radioButton_strain_gauge_right")
335  self.radioButton_measured_pwm = self._widget.findChild(QRadioButton, "radioButton_measured_pwm")
336  self.radioButton_measured_current = self._widget.findChild(QRadioButton, "radioButton_measured_current")
337  self.radioButton_measured_voltage = self._widget.findChild(QRadioButton, "radioButton_measured_voltage")
338  self.radioButton_measured_effort = self._widget.findChild(QRadioButton, "radioButton_measured_effort")
339  self.radioButton_temperature = self._widget.findChild(QRadioButton, "radioButton_temperature")
340  self.radioButton_unfiltered_position = self._widget.findChild(QRadioButton, "radioButton_unfiltered_position")
341  self.radioButton_unfiltered_force = self._widget.findChild(QRadioButton, "radioButton_unfiltered_force")
342  self.radioButton_last_commanded_effort = self._widget.findChild(QRadioButton,
343  "radioButton_last_commanded_effort")
344  self.radioButton_encoder_position = self._widget.findChild(QRadioButton, "radioButton_encoder_position")
345 
347  number_of_radio_button_pages = 3
348  for j in range(number_of_radio_button_pages):
349  for i in range(len(self.global_yaml["graphs"][j]["lines"])):
350  tmp = self._make_all_button_functions(i, all=False, type=j)
351  self.radio_button_list.append(tmp)
352  tmp = self._make_all_button_functions(i, all=True, type=j)
353  self.radio_button_list.append(tmp)
354 
355  self.radio_button_position.toggled.connect(lambda: self.radio_button_list[0](self.radio_button_position))
356  self.radio_button_velocity.toggled.connect(lambda: self.radio_button_list[1](self.radio_button_velocity))
357  self.radio_button_effort.toggled.connect(lambda: self.radio_button_list[2](self.radio_button_effort))
358  self.radio_button_all.toggled.connect(lambda: self.radio_button_list[3](self.radio_button_all))
359 
360  self.radio_button_setpoint.toggled.connect(lambda: self.radio_button_list[4](self.radio_button_setpoint))
361  self.radio_button_input.toggled.connect(lambda: self.radio_button_list[5](self.radio_button_input))
362  self.radio_button_dInput.toggled.connect(lambda: self.radio_button_list[6](self.radio_button_dInput))
363  self.radio_button_error.toggled.connect(lambda: self.radio_button_list[7](self.radio_button_error))
364  self.radio_button_output.toggled.connect(lambda: self.radio_button_list[8](self.radio_button_output))
365  self.radio_button_ctrl_all.toggled.connect(lambda: self.radio_button_list[9](self.radio_button_ctrl_all))
366 
367  self.radioButton_strain_gauge_left.toggled.connect(
368  lambda: self.radio_button_list[10](self.radioButton_strain_gauge_left))
369  self.radioButton_strain_gauge_right.toggled.connect(
370  lambda: self.radio_button_list[11](self.radioButton_strain_gauge_right))
371  self.radioButton_measured_pwm.toggled.connect(
372  lambda: self.radio_button_list[12](self.radioButton_measured_pwm))
373  self.radioButton_measured_current.toggled.connect(
374  lambda: self.radio_button_list[13](self.radioButton_measured_current))
375  self.radioButton_measured_voltage.toggled.connect(
376  lambda: self.radio_button_list[14](self.radioButton_measured_voltage))
377  self.radioButton_measured_effort.toggled.connect(
378  lambda: self.radio_button_list[15](self.radioButton_measured_effort))
379  self.radioButton_temperature.toggled.connect(
380  lambda: self.radio_button_list[16](self.radioButton_temperature))
381  self.radioButton_unfiltered_position.toggled.connect(
382  lambda: self.radio_button_list[17](self.radioButton_unfiltered_position))
383  self.radioButton_unfiltered_force.toggled.connect(
384  lambda: self.radio_button_list[18](self.radioButton_unfiltered_force))
385  self.radioButton_last_commanded_effort.toggled.connect(
387  self.radioButton_encoder_position.toggled.connect(
388  lambda: self.radio_button_list[20](self.radioButton_encoder_position))
389  self.radioButton_all_motor_stat.toggled.connect(
390  lambda: self.radio_button_list[21](self.radioButton_all_motor_stat))
391 
392  def _make_all_button_functions(self, i, all, type):
393  graph_type = self.type_dict[type]
394 
395  if "legend_columns" in self.global_yaml["graphs"][type]:
396  number_of_columns = self.global_yaml["graphs"][type]["legend_columns"]
397  elif all and graph_type == "pos_vel_eff":
398  number_of_columns = 3
399  elif all and graph_type == "control_loops":
400  number_of_columns = 5
401  elif all and graph_type == "motor_stat":
402  number_of_columns = 1
403 
404  if all:
405  def _button_function(b):
406  if b.text() == "All":
407  if b.isChecked():
408  self._change_graphs(all=True, type=type, ncol=number_of_columns)
409  else:
410  legend_name = self.global_yaml["graphs"][type]["lines"][i]
411  legend_name_stripped = re.sub(r"[\(\[].*?[\)\]]", "", legend_name).strip()
412 
413  def _button_function(b):
414  if legend_name_stripped in b.text():
415  if b.isChecked():
416  self._change_graphs(all=False, legend_name=[legend_name],
417  line_number=i, type=type, ncol=1)
418  return _button_function
419 
420  def _change_graphs(self, all, **kwargs):
421  index = kwargs["type"]
422  type = self.type_dict[index]
423 
424  if 'ncol' not in kwargs:
425  ncols = 3
426  else:
427  ncols = kwargs["ncol"]
428 
429  for i in range(len(self.graph_names_global[type])):
430  graph = self.graph_dict_global[type][self.graph_names_global[type][i]]
431  if all:
432  ymin, ymax = self._find_max_range(self.global_yaml["graphs"][index])
433  graph.ymin = ymin
434  graph.ymax = ymax
435  graph.plot_all = True
436  graph.ax1.yaxis.set_tick_params(which='both', labelbottom=False)
437  graph.re_init()
438  graph.ax1.legend(graph.line, self.global_yaml["graphs"][index]["lines"],
439  bbox_to_anchor=(0.0, 1.0, 1.0, 0.9), framealpha=0.8, loc=3, mode="expand",
440  borderaxespad=0.5, ncol=ncols,
441  prop={'size': 9 + self.font_offset})
442  else:
443  graph.ymin = self.global_yaml["graphs"][index]["ranges"][kwargs["line_number"]][0]
444  graph.ymax = self.global_yaml["graphs"][index]["ranges"][kwargs["line_number"]][1]
445  graph.line_to_plot = kwargs["line_number"]
446  graph.plot_all = False
447  graph.ax1.yaxis.set_tick_params(which='both', labelbottom=True, labelsize=6)
448  graph.re_init()
449  graph.ax1.legend(graph.line, kwargs["legend_name"], bbox_to_anchor=(0.0, 1.0, 1.0, 0.9),
450  framealpha=0.8, loc=3, mode="expand", borderaxespad=0.5,
451  prop={'size': 10 + self.font_offset})
452  if graph.enabled:
453  graph.update()
454  graph.draw()
455 
457  def _callback(value):
458  if graph.plot_all:
459  ymin, ymax = self._find_max_range(self.global_yaml["graphs"][1])
460  graph.addData(value.set_point * (ymax / self.global_yaml["graphs"][1]["ranges"][0][1]), 0)
461  graph.addData(value.process_value * (ymax / self.global_yaml["graphs"][1]["ranges"][1][1]), 1)
462  graph.addData(value.process_value_dot * (ymax / self.global_yaml["graphs"][1]["ranges"][2][1]), 2)
463  graph.addData(value.error * (ymax / self.global_yaml["graphs"][1]["ranges"][3][1]), 3)
464  graph.addData(value.command * (ymax / self.global_yaml["graphs"][1]["ranges"][4][1]), 4)
465  else:
466  graph.addData(value.set_point, 0)
467  graph.addData(value.process_value, 1)
468  graph.addData(value.process_value_dot, 2)
469  graph.addData(value.error, 3)
470  graph.addData(value.command, 4)
471 
472  return _callback
473 
474  def _find_max_range(self, graphs):
475  ymin = 0
476  ymax = 0
477  for i in range(len(graphs["ranges"])):
478  if graphs["ranges"][i][0] <= ymin and graphs["ranges"][i][1] >= ymax:
479  ymin = graphs["ranges"][i][0]
480  ymax = graphs["ranges"][i][1]
481  scales = [ymin, ymax]
482  return scales
483 
484  def _initialize(self, data):
485  self.global_yaml = data
486  topic_list = rospy.get_published_topics()
487  self.show_tactiles = False
488  for topic in topic_list:
489  for value in topic:
490  if "bio" in value or "Bio" in value:
492  self.show_tactiles = True
493  if self.show_tactiles is False:
494  for graphs in self.global_yaml["graphs"]:
495  if graphs["type"] == "biotacs":
496  self.global_yaml["graphs"].remove(graphs)
497  self.tab_widget_main.setTabEnabled(4, False)
498  self.tab_widget_main.setTabEnabled(5, False)
499  p = self.tab_widget_main.palette()
500  stylesheet = """
501  QTabBar::tab::disabled {width: 0; height: 0; margin: 0; padding: 1; border: none;}
502  QTabWidget>QWidget>QWidget{background: white;}
503  """
504  p.setColor(self.tab_widget_main.backgroundRole(), Qt.white)
505  self.tab_widget_main.setStyleSheet(stylesheet)
506 
509  self.subs = []
511  for graphs in data["graphs"]:
512  if self.show_tactiles or graphs["type"] != "biotacs":
513  ymin, ymax = self._find_max_range(graphs)
514  self.graph_names_global[graphs["type"]] = graphs["graph_names"]
515  if "legend_columns" in graphs:
516  legend_columns = graphs["legend_columns"]
517  else:
518  legend_columns = len(graphs["lines"])
519 
520  # create_graphs
521  temp_graph_dict = {}
522  for i in range(len(graphs["graph_names"])):
523  if graphs["type"] == "biotacs":
524  temp_graph_dict[graphs["graph_names"][i]] = CustomFigCanvas(num_lines=len(graphs["lines"]),
525  colour=graphs["colours"],
526  ymin=graphs["ranges"][i][0],
527  ymax=graphs["ranges"][i][1],
528  legends=graphs["lines"],
529  legend_columns=legend_columns,
530  legend_font_size=(
531  graphs["font_size"] +
532  self.font_offset),
533  num_ticks=4,
534  xaxis_tick_animation=False,
535  tail_enable=False, enabled=True)
536  else:
537  temp_graph_dict[graphs["graph_names"][i]] = CustomFigCanvas(num_lines=len(graphs["lines"]),
538  colour=graphs["colours"], ymin=ymin,
539  ymax=ymax, legends=graphs["lines"],
540  legend_columns=legend_columns,
541  legend_font_size=(
542  9 +
543  self.font_offset),
544  num_ticks=4,
545  xaxis_tick_animation=False,
546  tail_enable=False, enabled=True)
547  self.graph_dict_global[graphs["type"]] = temp_graph_dict
548 
549  # create subscribers
550  if graphs["type"] == "control_loops":
551  for i in range(len(graphs["graph_names"])):
552  sub_namespace = graphs["topic_namespace_start"] + graphs["graph_names"][i] + graphs[
553  "topic_namespace_end"]
554  tmp_callback = self._make_control_loop_callbacks(
555  self.graph_dict_global["control_loops"][graphs["graph_names"][i]])
556  self.subs.append(
557  rospy.Subscriber(sub_namespace, JointControllerState, callback=tmp_callback, queue_size=1))
558  self.control_loop_callback_dict[graphs["graph_names"][i]] = tmp_callback
559  elif graphs["type"] == "pos_vel_eff":
560  self.subs.append(
561  rospy.Subscriber(graphs["topic_namespace"], JointState, self._joint_state_cb, queue_size=1))
562  elif graphs["type"] == "motor_stat":
563  self.subs.append(
564  rospy.Subscriber(graphs["topic_namespace"], DiagnosticArray, self._diagnostic_cb,
565  queue_size=1))
566  elif graphs["type"] == "palm_extras_accelerometer":
567  self.subs.append(
568  rospy.Subscriber(graphs["topic_namespace"], Float64MultiArray, self._palm_extras_cb,
569  queue_size=1))
570  elif graphs["type"] == "biotacs":
571  self.subs.append(
572  rospy.Subscriber(graphs["topic_namespace"], BiotacAll, self._biotac_all_cb, queue_size=1))
573 
574  # init_widget_children
575  lay_dic = {}
576  for i in range(len(graphs["graph_names"])):
577  if graphs["type"] == "control_loops":
578  layout = graphs["graph_names"][i] + "_layout_ctrl"
579  elif graphs["type"] == "motor_stat":
580  layout = graphs["graph_names"][i] + "_layout_motor_stat"
581  else:
582  layout = graphs["graph_names"][i] + "_layout"
583  lay_dic[graphs["graph_names"][i]] = self._widget.findChild(QVBoxLayout, layout)
584  # attach_graphs
585  for i in range(len(graphs["graph_names"])):
586  x = lay_dic.get(graphs["graph_names"][i])
587  x.addWidget(self.graph_dict_global[graphs["type"]][graphs["graph_names"][i]])
588  # Setup palm extras graphs (as they don't need radio buttons)
589  palm_extras_graphs = [value for key, value in self.graph_dict_global.items() if 'palm_extras' in key]
590  i = 3
591  for graph in palm_extras_graphs:
592  for key, value in graph.iteritems():
593  value.plot_all = True
594  value.ax1.yaxis.set_tick_params(which='both', labelbottom=True)
595  value.ymax = self.global_yaml["graphs"][i]["ranges"][0][1]
596  value.ymin = self.global_yaml["graphs"][i]["ranges"][0][0]
597  font_size = value.ax1.legend_.prop._size
598  value.re_init()
599  value.ax1.legend(value.line, self.global_yaml["graphs"][i]["lines"],
600  bbox_to_anchor=(0.0, 1.0, 1.0, 0.9), framealpha=0.8, loc=3, mode="expand",
601  borderaxespad=0.5, ncol=len(self.global_yaml["graphs"][i]["lines"]),
602  prop={'size': font_size})
603  i += 1
604 
605  def _joint_state_cb(self, value):
606  if self.first_run:
607  # Creates map of jointstates (so we can do joint_state.values.position[joint_state_data_map["rh_FFJ1"]]
609  for i in range(len(value.name)):
610  self.joint_state_data_map[value.name[i]] = i
611  self.first_run = False
612  # Only add data to graphs once they've all been created
613  if self.init_complete:
614  # for each graph
615  for j in range(len(self.graph_names_global["pos_vel_eff"])):
616  graph = self.graph_dict_global["pos_vel_eff"][self.graph_names_global["pos_vel_eff"][j]]
617  data_index = self.joint_state_data_map[self._joint_prefix +
618  string.upper(self.graph_names_global["pos_vel_eff"][j])]
619  if graph.plot_all:
620  ymin, ymax = self._find_max_range(self.global_yaml["graphs"][0])
621  range_array = self.global_yaml["graphs"][0]["ranges"]
622  # for each line
623  graph.addData(value.position[data_index] * (ymax / range_array[0][1]), 0)
624  graph.addData(value.velocity[data_index] * (ymax / range_array[1][1]), 1)
625  graph.addData(value.effort[data_index] * (ymax / range_array[2][1]), 2)
626  else:
627  # for each line
628  graph.addData(value.position[data_index], 0)
629  graph.addData(value.velocity[data_index], 1)
630  graph.addData(value.effort[data_index], 2)
631 
632  def _diagnostic_cb(self, data):
633  # Only add data to graphs once they've all been created
634  if self.init_complete:
635  if len(data.status) > 1:
636  # for each joint_name / graph
637  # i iterate from 0 to give joint names #j iterate from 0 to give line numbers
638  for i in range(len(self.graph_names_global["motor_stat"])):
639  for j in range(len(self.motor_stat_keys[1])):
640  x = self.global_yaml["graphs"][2]["lines"][j]
641  x = re.sub(r"[\(\[].*?[\)\]]", "", x).strip()
642  ymin, ymax = self._find_max_range(self.global_yaml["graphs"][2])
643  graph = self.graph_dict_global["motor_stat"][self.graph_names_global["motor_stat"][i]]
644  data_index = self.motor_stat_keys[0][string.upper(self.graph_names_global["motor_stat"][i])]
645  data_point = data.status[data_index]
646  line_number = self.motor_stat_keys[1][x]
647  try:
648  data_value = data_point.values[line_number].value
649  except IndexError as e:
650  rospy.logerr("Can't find %s. Exception: %s", data_point.name, e)
651  data_value = 0
652  scale = float(ymax / self.global_yaml["graphs"][2]["ranges"][j][1])
653  if self.graph_dict_global["motor_stat"][self.graph_names_global["motor_stat"][i]].plot_all:
654  graph.addData(float(data_value) * scale, j)
655  else:
656  graph.addData(float(data_value), j)
657 
658  def _palm_extras_cb(self, data):
659  if self.init_complete:
660  palm_extras_graphs = [value for key, value in self.graph_dict_global.items() if 'palm_extras' in key]
661  for graph in palm_extras_graphs:
662  if 'palm_extras_accelerometer' in graph:
663  graph["palm_extras_accelerometer"].addData(data.data[0], 0)
664  graph["palm_extras_accelerometer"].addData(data.data[1], 1)
665  graph["palm_extras_accelerometer"].addData(data.data[2], 2)
666  if 'palm_extras_gyro' in graph:
667  graph["palm_extras_gyro"].addData(data.data[3], 0)
668  graph["palm_extras_gyro"].addData(data.data[4], 1)
669  graph["palm_extras_gyro"].addData(data.data[5], 2)
670  if 'palm_extras_adc' in graph:
671  graph["palm_extras_adc"].addData(data.data[6], 0)
672  graph["palm_extras_adc"].addData(data.data[7], 1)
673  graph["palm_extras_adc"].addData(data.data[8], 2)
674  graph["palm_extras_adc"].addData(data.data[9], 3)
675 
676  def _biotac_all_cb(self, data):
677  if self.init_complete:
678  for i in range(len(data.tactiles)):
679  self.graph_dict_global["biotacs"]["PAC0"].addData(data.tactiles[i].pac0, i)
680  self.graph_dict_global["biotacs"]["PAC1"].addData(data.tactiles[i].pac1, i)
681  self.graph_dict_global["biotacs"]["PDC"].addData(data.tactiles[i].pdc, i)
682  self.graph_dict_global["biotacs"]["TAC"].addData(data.tactiles[i].tac, i)
683  self.graph_dict_global["biotacs"]["TDC"].addData(data.tactiles[i].tdc, i)
684 
685 
687  _nb_electrodes_biotac = 19
688  _nb_electrodes_biotac_sp = 24
689 
690  def __init__(self, context):
691  super(SrGuiBiotac, self).__init__(context)
692  self.setObjectName('SrGuiBiotac')
693  self._hand_finder = HandFinder()
694  self._hand_parameters = self._hand_finder.get_hand_parameters()
695  self.load_params()
696 
697  self._widget = QWidget()
698 
699  self.latest_data = BiotacAll()
700  self.pixels = self._widget.width() * self._widget.height()
701 
702  self.define_electrodes()
705 
707 
708  def define_electrodes(self):
710  rospy.get_param(
711  "sr_gui_biotac/sensing_electrodes_x_locations",
712  [6.45, 3.65, 3.65, 6.45, 3.65, 6.45, 0.00, 1.95, -1.95,
713  0.00, -6.45, - 3.65, -3.65, -6.45, -3.65, -6.45, 0.00,
714  0.00, 0.00]) # Physical electrode locations on the sensor
716  rospy.get_param(
717  "sr_gui_biotac/sensing_electrodes_y_locations",
718  [7.58, 11.28, 14.78, 16.58, 19.08, 21.98, 4.38, 6.38, 6.38,
719  8.38, 7.58, 11.28, 14.78, 16.58, 19.08, 21.98, 11.38,
720  18.38, 22.18])
721 
723  rospy.get_param(
724  "sr_gui_biotac/excitation_electrodes_x_locations",
725  [6.45, 3.75, -3.75, -6.45])
727  rospy.get_param(
728  "sr_gui_biotac/excitation_electrodes_y_locations",
729  [12.48, 24.48, 24.48, 12.48])
730 
732  rospy.get_param(
733  "sr_gui_biotac/sensing_electrodes_x_locations",
734  [5.00, 3.65, 6.45, 4.40, 2.70, 6.45, 4.40, 1.50, 4.00, 4.50,
735  -5.00, - 3.65, -6.45, -4.40, -2.70, -6.45, -4.40, -1.50, -4.00, -4.50,
736  0.00, 1.95, -1.95, 0.00]) # Physical electrode locations on the sensor
738  rospy.get_param(
739  "sr_gui_biotac/sensing_electrodes_y_locations",
740  [4.38, 6.38, 14.78, 15.50, 18.50, 19.08, 20.00, 21.00, 23.00, 25.00,
741  4.38, 6.38, 14.78, 15.50, 18.50, 19.08, 20.00, 21.00, 23.00, 25.00,
742  7.38, 11.50, 11.50, 15.20])
743 
745  rospy.get_param(
746  "sr_gui_biotac/excitation_electrodes_x_locations",
747  [5.30, 6.00, -5.30, -6.00])
749  rospy.get_param(
750  "sr_gui_biotac/excitation_electrodes_y_locations",
751  [9.00, 22.00, 9.00, 22.00])
752 
753  def _assign_electrodes(self, nb_electrodes):
754  if nb_electrodes == self._nb_electrodes_biotac:
759  elif nb_electrodes == self._nb_electrodes_biotac_sp:
764  else:
765  rospy.logerr("Number of electrodes %d not matching known biotac models. expected: %d or %d",
766  nb_electrodes, self._nb_electrodes_biotac, self._nb_electrodes_biotac_sp)
767  return
768 
769  for n in range(len(self.sensing_electrodes_x)):
770  self.sensing_electrodes_x[n] = (
771  self.sensing_electrodes_x[n] * self.factor +
772  self.x_display_offset[0])
773  self.sensing_electrodes_y[n] = (
774  self.sensing_electrodes_y[n] * self.factor +
775  self.y_display_offset[0])
776 
777  for n in range(len(self.excitation_electrodes_x)):
778  self.excitation_electrodes_x[n] = (
779  self.excitation_electrodes_x[n] * self.factor +
780  self.x_display_offset[0])
781  self.excitation_electrodes_y[n] = (
782  self.excitation_electrodes_y[n] * self.factor +
783  self.y_display_offset[0])
784 
785  def _tactile_cb(self, msg):
786  if len(msg.tactiles[0].electrodes) != self._nb_electrodes:
787  self._nb_electrodes = len(msg.tactiles[0].electrodes)
789  self.latest_data = msg
790 
792  r = 0.0
793  g = 0.0
794  b = 255.0
795 
796  value = float(value)
797 
798  threshold = (0.0, 1000.0, 2000.0, 3000.0, 4095.0)
799 
800  if value <= threshold[0]:
801  pass
802 
803  elif value < threshold[1]:
804  r = 255
805  g = 255 * ((value - threshold[0]) / (threshold[1] - threshold[0]))
806  b = 0
807 
808  elif value < threshold[2]:
809  r = 255 * ((threshold[2] - value) / (threshold[2] - threshold[1]))
810  g = 255
811  b = 0
812 
813  elif value < threshold[3]:
814  r = 0
815  g = 255
816  b = 255 * ((value - threshold[2]) / (threshold[3] - threshold[2]))
817  elif value < threshold[4]:
818  r = 0
819  g = 255 * ((threshold[4] - value) / (threshold[4] - threshold[3]))
820  b = 255
821 
822  return QColor(r, g, b)
823 
824  def _draw_electrode(self, painter, elipse_x, elipse_y, text_x, text_y, colour, text):
825 
826  rect = QRectF(elipse_x, elipse_y, self.RECTANGLE_WIDTH,
827  self.RECTANGLE_HEIGHT)
828 
829  painter.setBrush(colour)
830  painter.drawEllipse(rect)
831 
832  rect.setX(text_x)
833  rect.setY(text_y)
834 
835  painter.drawText(rect, text)
836 
837  def paintEvent(self, paintEvent):
838  painter = QPainter(self.widget)
839  which_tactile = self.biotac_name
840 
841  painter.setFont(QFont("Arial", self.label_font_size[0]))
842 
843  if len(self.sensing_electrodes_x) == len(self.latest_data.tactiles[which_tactile].electrodes):
844  for n in range(len(self.sensing_electrodes_x)):
845  value = self.latest_data.tactiles[which_tactile].electrodes[n]
846 
847  eval("self._widget.lcdE%02d_%d.display(%d)" % (n + 1, self.biotac_name, value))
848  colour = self._get_electrode_colour_from_value(value)
849 
850  elipse_x = self.sensing_electrodes_x[n]
851  elipse_y = self.sensing_electrodes_y[n]
852 
853  if n < 9:
854  text_x = elipse_x + self.x_display_offset[1]
855  text_y = elipse_y + self.y_display_offset[1]
856 
857  else:
858  text_x = elipse_x + self.x_display_offset[2]
859  text_y = elipse_y + self.y_display_offset[2]
860 
861  self._draw_electrode(painter, elipse_x, elipse_y, text_x, text_y, colour, str(n + 1))
862 
863  painter.setFont(QFont("Arial", self.label_font_size[1]))
864 
865  for n in range(len(self.excitation_electrodes_x)):
866  elipse_x = self.excitation_electrodes_x[n]
867  elipse_y = self.excitation_electrodes_y[n]
868 
869  colour = QColor(127, 127, 127)
870 
871  text_x = elipse_x + self.x_display_offset[3]
872  text_y = elipse_y + self.y_display_offset[3]
873 
874  self._draw_electrode(painter, elipse_x, elipse_y, text_x, text_y,
875  colour, "X" + str(n + 1))
876 
877  self._widget.update()
878 
879  def _subscribe_to_topic(self, prefix):
880  if prefix:
881  rospy.Subscriber(prefix + "tactile", BiotacAll, self._tactile_cb)
882 
883  def load_params(self):
884 
885  self.RECTANGLE_WIDTH = rospy.get_param(
886  "sr_gui_biotac/electrode_display_width",
887  30) # Display sizes for electrodes in pixels
888  self.RECTANGLE_HEIGHT = rospy.get_param(
889  "sr_gui_biotac/electrode_display_height", 30)
890 
891  self.factor = 5
892  # location on the sensor in mm to display location in pixels
893  self.x_display_offset = rospy.get_param(
894  "sr_gui_biotac/x_display_offset", [125, 12.5, 4.5,
895  3.5]) # Pixel offsets for
896  # displaying electrodes. offset[0] is applied to each electrode.
897  # 1,2 and 3 are the label offsets for displaying electrode number.
898  self.y_display_offset = rospy.get_param(
899  "sr_gui_biotac/y_display_offset", [-30, 4.0, 4.0, 4.0])
900  self.label_font_size = rospy.get_param(
901  "sr_gui_biotac/electrode_label_font_sizes", [8,
902  6]) # Font sizes
903  # for labels on sensing + excitation electrodes
904 
905  if self._hand_parameters.mapping:
906  self.default_topic = (
907  self._hand_parameters.mapping.values()[0] + '/')
908  else:
909  self.default_topic = ""
910 
911  def find_children(self, biotac_name):
912  self.widget = self._widget.findChild(QWidget, "widget" + "_" + str(biotac_name))
913  self.biotac_name = biotac_name
914 
915  def redraw_electrodes(self):
916  self.pixels = self._widget.width() * self._widget.height()
917  self.define_electrodes()
918 
919  if self._nb_electrodes == self._nb_electrodes_biotac:
920  self.factor = 17.5
921  elif self._nb_electrodes == self._nb_electrodes_biotac_sp:
922  self.factor = 25.0
923  else:
924  rospy.logerr("Number of electrodes %d not matching known biotac models. expected: %d or %d",
925  self.nb_electrodes, self._nb_electrodes_biotac, self._nb_electrodes_biotac_sp)
926  return
927 
928  if self.pixels > 3500000:
929  self.factor = self.factor * 0.80
930  self.RECTANGLE_WIDTH = 40
931  self.RECTANGLE_HEIGHT = 40
932  self.x_display_offset[0] = 170
933  self.y_display_offset[0] = -30
934  self.label_font_size = [10, 9]
935  else:
936  self.factor = self.factor * 0.55
937  self.RECTANGLE_WIDTH = 25
938  self.RECTANGLE_HEIGHT = 25
939  self.x_display_offset[0] = 125
940  self.y_display_offset[0] = -30
941  self.label_font_size = [8, 8]
942 
945 
946 
947 class CustomFigCanvas(FigureCanvas, TimedAnimation):
948  def __init__(self, num_lines, colour=[], ymin=-1, ymax=1, legends=[], legend_columns='none', legend_font_size=7,
949  num_ticks=4, xaxis_tick_animation=False, tail_enable=True, enabled=True):
950  self.plot_all = True
951  self.line_to_plot = None
952  self.enabled = enabled
953  self.legends = legends
954  self.num_lines = num_lines
955  self.num_ticks = num_ticks
956  self.tail_enable = tail_enable
957  self.legend_columns = legend_columns
958  self.legend_font_size = legend_font_size
959  self.xaxis_tick_animation = xaxis_tick_animation
960  self.ymin = ymin
961  self.ymax = ymax
962  self.colour = colour
963  if legend_columns == 'none':
964  legend_columns = self.num_lines
965  self.addedDataArray = []
966  self.start_time = rospy.get_rostime()
967  for n in range(self.num_lines):
968  addedData = []
969  self.addedDataArray.append(addedData)
970 
971  # The data
972  self.xlim = 200
973  self.n = np.linspace(0, self.xlim - 1, self.xlim)
974  self.y = []
975  for n in range(self.num_lines):
976  self.y.append((self.n * 0.0) + 50)
977 
978  self.label_buffer = []
979 
980  # The window
981  self.fig = Figure(figsize=(3, 3), dpi=100, facecolor=(1.0, 1.0, 1.0, 1.0))
982  # self.fig.patch.set_alpha(0.0)
983  self.ax1 = self.fig.add_subplot(111)
984  self.x_axis = self.n
985  if not self.xaxis_tick_animation:
986  self.ax1.axes.get_xaxis().set_visible(False)
987 
988  # Shrink the font size of the x tick labels
989  for tick in self.ax1.yaxis.get_major_ticks():
990  tick.label.set_fontsize(7)
991  self.ax1.yaxis.grid(True, linestyle='-', which='major', color='lightgrey', alpha=0.5)
992  self.ax1.yaxis.set_tick_params(which='both', labelbottom=False)
993 
994  self.line = []
995  if self.tail_enable:
996  self.line_head = []
997  self.line_tail = []
998  for i in range(self.num_lines):
999  self.line.append(Line2D([], [], color=self.colour[i]))
1000  if self.tail_enable:
1001  self.line_tail.append(Line2D([], [], color='red', linewidth=2))
1002  self.line_head.append(Line2D([], [], color='red', marker='o', markeredgecolor='r'))
1003  self.ax1.add_line(self.line_tail[i])
1004  self.ax1.add_line(self.line_head[i])
1005  self.ax1.add_line(self.line[i])
1006  self.ax1.set_xlim(0, self.xlim - 1)
1007  self.ax1.set_ylim(ymin, ymax)
1008 
1009  self.fig.subplots_adjust(bottom=0.05, top=0.8, left=0.08, right=0.98)
1010  self.ax1.legend(self.line, self.legends, bbox_to_anchor=(0.0, 1.0, 1.0, 0.9), framealpha=0.8, loc=3,
1011  ncol=legend_columns, mode="expand", borderaxespad=0.5, prop={'size': legend_font_size})
1012  FigureCanvas.__init__(self, self.fig)
1013  TimedAnimation.__init__(self, self.fig, interval=50, blit=not self.xaxis_tick_animation)
1014 
1015  def re_init(self):
1016  self.line = []
1017  if self.tail_enable:
1018  self.line_head = []
1019  self.line_tail = []
1020 
1021  if self.plot_all:
1022  for i in range(self.num_lines):
1023  self.line.append(Line2D([], [], color=self.colour[i]))
1024  if self.tail_enable:
1025  self.line_tail.append(Line2D([], [], color='red', linewidth=2))
1026  self.line_head.append(Line2D([], [], color='red', marker='o', markeredgecolor='r'))
1027  self.ax1.add_line(self.line_tail[i])
1028  self.ax1.add_line(self.line_head[i])
1029  self.ax1.add_line(self.line[i])
1030  self.ax1.set_xlim(0, self.xlim - 1)
1031  self.ax1.set_ylim(self.ymin, self.ymax)
1032  else:
1033  for i in range(self.num_lines):
1034  self.line.append(Line2D([], [], color=self.colour[self.line_to_plot]))
1035  if self.tail_enable:
1036  self.line_tail.append(Line2D([], [], color='red', linewidth=2))
1037  self.line_head.append(Line2D([], [], color='red', marker='o', markeredgecolor='r'))
1038  self.ax1.add_line(self.line_tail[i])
1039  self.ax1.add_line(self.line_head[i])
1040  self.ax1.add_line(self.line[i])
1041  self.ax1.set_xlim(0, self.xlim - 1)
1042  self.ax1.set_ylim(self.ymin, self.ymax)
1043 
1044  def new_frame_seq(self):
1045  return iter(range(self.n.size))
1046 
1047  def _init_draw(self):
1048  for i in range(self.num_lines):
1049  if self.tail_enable:
1050  lines = [self.line[i], self.line_tail[i], self.line_head[i]]
1051  else:
1052  lines = [self.line[i]]
1053  for l in lines:
1054  l.set_data([], [])
1055 
1056  def addData(self, value, index):
1057  self.addedDataArray[index].append(value)
1058  if len(self.addedDataArray[index]) > (self.xlim * 2):
1059  del self.addedDataArray[index][0:self.xlim]
1060 
1061  def _step(self, *args):
1062  if self.enabled:
1063  TimedAnimation._step(self, *args)
1064 
1065  def _draw_frame(self, framedata):
1066  margin = 2
1067  for i in range(self.num_lines):
1068  while len(self.addedDataArray[i]) > 0:
1069  self.y[i] = np.roll(self.y[i], -1)
1070  self.y[i][-1] = self.addedDataArray[i][0]
1071  del (self.addedDataArray[i][0])
1072  if self.plot_all:
1073  for i in range(self.num_lines):
1074  self.line[i].set_data(self.n[0: self.n.size - margin], self.y[i][0: self.n.size - margin])
1075  if self.tail_enable:
1076  self.line_tail[i].set_data(np.append(self.n[-10:-1 - margin], self.n[-1 - margin]),
1077  np.append(self.y[i][-10:-1 - margin], self.y[i][-1 - margin]))
1078  self.line_head[i].set_data(self.n[-1 - margin], self.y[i][-1 - margin])
1079  self._drawn_artists = []
1080  for l in self.line:
1081  self._drawn_artists.append(l)
1082  if self.tail_enable:
1083  for l in self.line_tail:
1084  self._drawn_artists.append(l)
1085  for l in self.line_head:
1086  self._drawn_artists.append(l)
1087  else:
1088  i = self.line_to_plot
1089  self.line[i].set_data(self.n[0: self.n.size - margin], self.y[i][0: self.n.size - margin])
1090  if self.tail_enable:
1091  self.line_tail[i].set_data(np.append(self.n[-10:-1 - margin], self.n[-1 - margin]),
1092  np.append(self.y[i][-10:-1 - margin], self.y[i][-1 - margin]))
1093  self.line_head[i].set_data(self.n[-1 - margin], self.y[i][-1 - margin])
1094  self._drawn_artists = []
1095  for l in self.line:
1096  self._drawn_artists.append(l)
1097  if self.tail_enable:
1098  for l in self.line_tail:
1099  self._drawn_artists.append(l)
1100  for l in self.line_head:
1101  self._drawn_artists.append(l)
1102 
1103  if self.xaxis_tick_animation:
1104  time_from_start = int((rospy.get_rostime() - self.start_time).to_sec())
1105  if len(self.label_buffer) > 3:
1106  self.label_buffer = np.roll(self.label_buffer, 1)
1107  self.label_buffer[2] = time_from_start
1108  else:
1109  self.label_buffer.append(time_from_start)
1110  x = []
1111  for i in range(self.num_ticks):
1112  x.append(int(self.xlim / self.num_ticks) * i)
1113  self.ax1.set_xticks(x)
1114  self.ax1.set_xticklabels([int(i / int(self.xlim / self.num_ticks)) + time_from_start for i in x])
1115 
1116 
1117 if __name__ == "__main__":
1118  rospy.init_node("hand_e_visualizer")
1119  app = QApplication(sys.argv)
1120  data_visualiser_gui = SrDataVisualizer(None)
1121  data_visualiser_gui._widget.show()
1122  atexit.register(data_visualiser_gui.shutdown_plugin)
1123  signal.signal(signal.SIGINT, signal.SIG_DFL)
1124  sys.exit(app.exec_())
def __init__(self, num_lines, colour=[], ymin=-1, ymax=1, legends=[], legend_columns='none', legend_font_size=7, num_ticks=4, xaxis_tick_animation=False, tail_enable=True, enabled=True)
def _draw_electrode(self, painter, elipse_x, elipse_y, text_x, text_y, colour, text)


sr_data_visualization
Author(s): Tom Queen
autogenerated on Mon Feb 28 2022 23:51:19