28 matplotlib.use(
"Qt5Agg")
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
43 from python_qt_binding
import loadUi
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
63 super(SrDataVisualizer, self).
__init__(context)
64 self.setObjectName(
"SrDataVisualizer")
70 for hand, joints
in self.
_hand_finder.hand_joints.items():
76 ui_file = os.path.join(rospkg.RosPack().get_path(
'sr_data_visualization'),
'uis',
'hand-e_visualizer.ui')
78 if __name__ !=
"__main__":
79 context.add_widget(self.
_widget)
80 self.
_widget.setWindowTitle(
"Dexterous Hand Data Visualizer")
84 p.setColor(self.
_widget.backgroundRole(), Qt.white)
92 QTabWidget>QWidget>QWidget{background: white;} 100 motor_stat_keys_file = os.path.join(rospkg.RosPack().get_path(
'sr_data_visualization'),
'config',
101 'data_visualiser_motor_stat_keys.yaml')
103 parameters_file = os.path.join(rospkg.RosPack().get_path(
'sr_data_visualization'),
'config',
104 'data_visualiser_parameters_rh_lite.yaml')
106 parameters_file = os.path.join(rospkg.RosPack().get_path(
'sr_data_visualization'),
'config',
107 'data_visualiser_parameters_rh.yaml')
109 parameters_file = os.path.join(rospkg.RosPack().get_path(
'sr_data_visualization'),
'config',
110 'data_visualiser_parameters_lh.yaml')
112 rospy.logerr(
"Unknown hand detected")
114 self.
t0 = time.time()
136 with open(motor_stat_keys_file,
'r') as stream: 139 except yaml.YAMLError
as exc:
142 with open(parameters_file,
'r') as stream: 144 data_loaded = yaml.load(stream)
146 except yaml.YAMLError
as exc:
162 QTimer.singleShot(5000, self.
reset_1)
167 for element
in graph_type:
169 graph.enabled =
False 192 for element
in graph_type:
195 graph._handle_resize()
207 tactile_gui._widget = self.
_widget 208 tactile_gui.find_children(i)
210 widget = self.
_widget.findChild(QWidget,
"widget" +
"_" + str(i))
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")
226 lcd = self.
_widget.findChild(QLCDNumber,
"lcdE0" + str(i) +
"_" + str(j))
227 label = self.
_widget.findChild(QLabel,
"label_E0" + str(i) +
"_" + str(j))
229 lcd = self.
_widget.findChild(QLCDNumber,
"lcdE" + str(i) +
"_" + str(j))
230 label = self.
_widget.findChild(QLabel,
"label_E" + str(i) +
"_" + str(j))
239 tactile_widget.redraw_electrodes()
248 font = QFont(
'Sans Serif', scale)
249 font.setKerning(
True)
252 self.
lcd_list[j][i].setMinimumHeight(2)
253 self.
lcd_list[j][i].setMaximumHeight(mheight)
268 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "pos_vel_eff" not in key]
272 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "control_loops" not in key]
276 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "motor_stat" not in key]
280 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "palm_extras" not in key]
282 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "palm_extras" in key]
285 graph_type = [key
for key, value
in self.
graph_names_global.items()
if "biotacs" not in key]
291 elif tab ==
"motor_stat":
307 x = [value
for key, value
in self.
graph_dict_global[
"motor_stat"].items()
if joint_group
in key]
310 x = [value
for key, value
in self.
graph_dict_global[
"motor_stat"].items()
if joint_group
not in key]
312 graph.enabled =
False 315 for element
in graph_type:
317 graph.enabled =
not disable
343 "radioButton_last_commanded_effort")
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"])):
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
405 def _button_function(b):
406 if b.text() ==
"All":
410 legend_name = self.
global_yaml[
"graphs"][type][
"lines"][i]
411 legend_name_stripped = re.sub(
r"[\(\[].*?[\)\]]",
"", legend_name).strip()
413 def _button_function(b):
414 if legend_name_stripped
in b.text():
417 line_number=i, type=type, ncol=1)
418 return _button_function
421 index = kwargs[
"type"]
424 if 'ncol' not in kwargs:
427 ncols = kwargs[
"ncol"]
435 graph.plot_all =
True 436 graph.ax1.yaxis.set_tick_params(which=
'both', labelbottom=
False)
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,
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)
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,
457 def _callback(value):
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)
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)
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]
486 topic_list = rospy.get_published_topics()
488 for topic
in topic_list:
490 if "bio" in value
or "Bio" in value:
495 if graphs[
"type"] ==
"biotacs":
501 QTabBar::tab::disabled {width: 0; height: 0; margin: 0; padding: 1; border: none;} 502 QTabWidget>QWidget>QWidget{background: white;} 511 for graphs
in data[
"graphs"]:
515 if "legend_columns" in graphs:
516 legend_columns = graphs[
"legend_columns"]
518 legend_columns = len(graphs[
"lines"])
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,
531 graphs[
"font_size"] +
534 xaxis_tick_animation=
False,
535 tail_enable=
False, enabled=
True)
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,
545 xaxis_tick_animation=
False,
546 tail_enable=
False, enabled=
True)
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"]
557 rospy.Subscriber(sub_namespace, JointControllerState, callback=tmp_callback, queue_size=1))
559 elif graphs[
"type"] ==
"pos_vel_eff":
561 rospy.Subscriber(graphs[
"topic_namespace"], JointState, self.
_joint_state_cb, queue_size=1))
562 elif graphs[
"type"] ==
"motor_stat":
564 rospy.Subscriber(graphs[
"topic_namespace"], DiagnosticArray, self.
_diagnostic_cb,
566 elif graphs[
"type"] ==
"palm_extras_accelerometer":
568 rospy.Subscriber(graphs[
"topic_namespace"], Float64MultiArray, self.
_palm_extras_cb,
570 elif graphs[
"type"] ==
"biotacs":
572 rospy.Subscriber(graphs[
"topic_namespace"], BiotacAll, self.
_biotac_all_cb, queue_size=1))
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" 582 layout = graphs[
"graph_names"][i] +
"_layout" 583 lay_dic[graphs[
"graph_names"][i]] = self.
_widget.findChild(QVBoxLayout, layout)
585 for i
in range(len(graphs[
"graph_names"])):
586 x = lay_dic.get(graphs[
"graph_names"][i])
589 palm_extras_graphs = [value
for key, value
in self.
graph_dict_global.items()
if 'palm_extras' in key]
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
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})
609 for i
in range(len(value.name)):
621 range_array = self.
global_yaml[
"graphs"][0][
"ranges"]
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)
628 graph.addData(value.position[data_index], 0)
629 graph.addData(value.velocity[data_index], 1)
630 graph.addData(value.effort[data_index], 2)
635 if len(data.status) > 1:
641 x = re.sub(
r"[\(\[].*?[\)\]]",
"", x).strip()
645 data_point = data.status[data_index]
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)
652 scale = float(ymax / self.
global_yaml[
"graphs"][2][
"ranges"][j][1])
654 graph.addData(float(data_value) * scale, j)
656 graph.addData(float(data_value), j)
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)
678 for i
in range(len(data.tactiles)):
687 _nb_electrodes_biotac = 19
688 _nb_electrodes_biotac_sp = 24
691 super(SrGuiBiotac, self).
__init__(context)
692 self.setObjectName(
'SrGuiBiotac')
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,
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,
724 "sr_gui_biotac/excitation_electrodes_x_locations",
725 [6.45, 3.75, -3.75, -6.45])
728 "sr_gui_biotac/excitation_electrodes_y_locations",
729 [12.48, 24.48, 24.48, 12.48])
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])
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])
746 "sr_gui_biotac/excitation_electrodes_x_locations",
747 [5.30, 6.00, -5.30, -6.00])
750 "sr_gui_biotac/excitation_electrodes_y_locations",
751 [9.00, 22.00, 9.00, 22.00])
765 rospy.logerr(
"Number of electrodes %d not matching known biotac models. expected: %d or %d",
798 threshold = (0.0, 1000.0, 2000.0, 3000.0, 4095.0)
800 if value <= threshold[0]:
803 elif value < threshold[1]:
805 g = 255 * ((value - threshold[0]) / (threshold[1] - threshold[0]))
808 elif value < threshold[2]:
809 r = 255 * ((threshold[2] - value) / (threshold[2] - threshold[1]))
813 elif value < threshold[3]:
816 b = 255 * ((value - threshold[2]) / (threshold[3] - threshold[2]))
817 elif value < threshold[4]:
819 g = 255 * ((threshold[4] - value) / (threshold[4] - threshold[3]))
822 return QColor(r, g, b)
829 painter.setBrush(colour)
830 painter.drawEllipse(rect)
835 painter.drawText(rect, text)
838 painter = QPainter(self.
widget)
845 value = self.
latest_data.tactiles[which_tactile].electrodes[n]
847 eval(
"self._widget.lcdE%02d_%d.display(%d)" % (n + 1, self.
biotac_name, value))
861 self.
_draw_electrode(painter, elipse_x, elipse_y, text_x, text_y, colour, str(n + 1))
869 colour = QColor(127, 127, 127)
875 colour,
"X" + str(n + 1))
881 rospy.Subscriber(prefix +
"tactile", BiotacAll, self.
_tactile_cb)
886 "sr_gui_biotac/electrode_display_width",
889 "sr_gui_biotac/electrode_display_height", 30)
894 "sr_gui_biotac/x_display_offset", [125, 12.5, 4.5,
899 "sr_gui_biotac/y_display_offset", [-30, 4.0, 4.0, 4.0])
901 "sr_gui_biotac/electrode_label_font_sizes", [8,
912 self.
widget = self.
_widget.findChild(QWidget,
"widget" +
"_" + str(biotac_name))
924 rospy.logerr(
"Number of electrodes %d not matching known biotac models. expected: %d or %d",
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):
963 if legend_columns ==
'none':
976 self.
y.append((self.
n * 0.0) + 50)
981 self.
fig = Figure(figsize=(3, 3), dpi=100, facecolor=(1.0, 1.0, 1.0, 1.0))
986 self.
ax1.axes.get_xaxis().set_visible(
False)
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)
999 self.
line.append(Line2D([], [], color=self.
colour[i]))
1001 self.
line_tail.append(Line2D([], [], color=
'red', linewidth=2))
1002 self.
line_head.append(Line2D([], [], color=
'red', marker=
'o', markeredgecolor=
'r')) 1005 self.ax1.add_line(self.line[i]) 1006 self.ax1.set_xlim(0, self.xlim - 1) 1007 self.ax1.set_ylim(ymin, ymax) 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)
1023 self.
line.append(Line2D([], [], color=self.
colour[i]))
1025 self.
line_tail.append(Line2D([], [], color=
'red', linewidth=2))
1026 self.
line_head.append(Line2D([], [], color=
'red', marker=
'o', markeredgecolor=
'r')) 1029 self.ax1.add_line(self.line[i]) 1030 self.ax1.set_xlim(0, self.xlim - 1) 1036 self.
line_tail.append(Line2D([], [], color=
'red', linewidth=2))
1037 self.
line_head.append(Line2D([], [], color=
'red', marker=
'o', markeredgecolor=
'r')) 1040 self.ax1.add_line(self.line[i]) 1041 self.ax1.set_xlim(0, self.xlim - 1) 1045 return iter(range(self.
n.size))
1052 lines = [self.
line[i]]
1063 TimedAnimation._step(self, *args)
1069 self.
y[i] = np.roll(self.
y[i], -1)
1074 self.
line[i].set_data(self.
n[0: self.
n.size - margin], self.
y[i][0: self.
n.size - margin])
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])
1089 self.
line[i].set_data(self.
n[0: self.
n.size - margin], self.
y[i][0: self.
n.size - margin])
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])
1104 time_from_start = int((rospy.get_rostime() - self.
start_time).to_sec())
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])
1117 if __name__ ==
"__main__":
1118 rospy.init_node(
"hand_e_visualizer")
1119 app = QApplication(sys.argv)
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 define_electrodes(self)
def _disable_graphs(self, graph_type, disable)
def _show_specific_motor_stat_tabs(self)
radioButton_measured_effort
def _reset_graphs(self, tab)
radioButton_unfiltered_force
radioButton_measured_voltage
radioButton_all_motor_stat
def _palm_extras_cb(self, data)
def _diagnostic_cb(self, data)
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 _get_electrode_colour_from_value(self, value)
def _draw_frame(self, framedata)
def tab_change(self, tab_index)
radioButton_last_commanded_effort
radioButton_unfiltered_position
def on_resize_tactile(self, none)
def _setup_radio_buttons(self)
def _biotac_all_cb(self, data)
radioButton_strain_gauge_left
radioButton_measured_current
def paintEvent(self, paintEvent)
def _make_all_button_functions(self, i, all, type)
def _hide_all_but(self, joint_group)
excitation_electrodes_v2_x
def _assign_electrodes(self, nb_electrodes)
def __init__(self, context)
def __init__(self, context)
def addData(self, value, index)
def _draw_electrode(self, painter, elipse_x, elipse_y, text_x, text_y, colour, text)
def _include_tactile_plugin(self)
int _nb_electrodes_biotac
def _hide_tabs(self, tab_index, tab)
def _hide_and_refresh(self, tab_index, tab_type)
radioButton_encoder_position
excitation_electrodes_v2_y
def _subscribe_to_topic(self, prefix)
def tab_change_mstat(self, tab_index)
def find_children(self, biotac_name)
def _make_control_loop_callbacks(self, graph)
def _find_max_range(self, graphs)
excitation_electrodes_v1_y
def _change_graphs(self, all, kwargs)
int _nb_electrodes_biotac_sp
def _tactile_cb(self, msg)
control_loop_callback_dict
excitation_electrodes_v1_x
def shutdown_plugin(self)
def _initialize(self, data)
radioButton_strain_gauge_right
def redraw_electrodes(self)
def _joint_state_cb(self, value)
def on_resize_main(self, empty)