plot_dwb_scores.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import os
3 import tkinter
4 import matplotlib.pyplot as plt
5 import numpy as np
6 
7 import rospy
8 from dwb_msgs.msg import LocalPlanEvaluation
9 
10 fig = None
11 rects = None
12 max_score = 0.0
13 
14 
15 def eval_cb(msg):
16  global fig, rects, max_score
17  labels = [s.name for s in msg.twists[msg.best_index].scores]
18  scaled_scores = [s.scale * s.raw_score for s in msg.twists[msg.best_index].scores]
19 
20  # reverse labels + scaled_scores to show the critics in the correct order top to bottom
21  labels.reverse()
22  scaled_scores.reverse()
23 
24  if not fig:
25  # init
26  y = np.arange(len(labels)) # the label locations
27  height = 0.35 # the height of the bars
28 
29  fig, ax = plt.subplots()
30  rects = ax.barh(y - height / 2, scaled_scores, height, label='scaled score')
31 
32  ax.set_ylabel('DWB Critics')
33  ax.set_title('Scaled scores')
34  ax.set_yticks(y)
35  ax.set_yticklabels(labels)
36 
37  fig.tight_layout()
38  fig.canvas.set_window_title('DWB Scores')
39 
40  # update axis limit
41  if max_score < max(scaled_scores):
42  max_score = max(scaled_scores)
43  plt.xlim(0.0, max_score)
44 
45  for rect, h in zip(rects, scaled_scores):
46  rect.set_width(h)
47  try:
48  fig.canvas.draw()
49  fig.canvas.flush_events()
50  except tkinter.TclError:
51  rospy.loginfo('Window was closed, exiting.')
52  os._exit(0)
53 
54 
55 def main():
56  rospy.init_node('plot_dwb_scores')
57  rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb)
58  rospy.loginfo('plot_dwb_scores ready.')
59  plt.ion()
60  rospy.spin()
61 
62 
63 if __name__ == '__main__':
64  main()


mir_dwb_critics
Author(s): Martin Günther
autogenerated on Sun Feb 14 2021 03:40:12