temperature_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2011 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, either version 2 of the License, or (at your option)
8 # any later version.
9 #
10 # This program is distributed in the hope that it will be useful, but WITHOUT
11 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
12 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 # more details.
14 #
15 # You should have received a copy of the GNU General Public License along
16 # with this program. If not, see <http://www.gnu.org/licenses/>.
17 #
18 
19 import rospy
20 from diagnostic_msgs.msg import DiagnosticArray
21 
22 import curses
23 import traceback
24 
25 CASE_WIDTH = 20
26 CASE_HEIGHT = 1
27 JOINT_NAMES = ["FFJ0", "FFJ3", "FFJ4",
28  "MFJ0", "MFJ3", "MFJ4",
29  "RFJ0", "RFJ3", "RFJ4",
30  "LFJ0", "LFJ3", "LFJ4",
31  "THJ1", "THJ2", "THJ3", "THJ4", "THJ5",
32  "WRJ1", "WRJ2"]
33 COOL = 50
34 WARM = 55
35 
36 
37 class Joint(object):
38  def __init__(self, screen, joint_name, x, y):
39  self.screen = screen
40  self.x = x
41  self.y = y
42  self.joint_name = joint_name
43  self.temperature = -1
44 
45  # self.window = self.screen.subwin(1, 15, self.y+1, self.x + 1)
46  self.refresh()
47 
48  def set_temperature(self, temperature):
49  self.temperature = temperature
50  self.refresh()
51 
52  def refresh(self):
53  self.screen.addstr(self.y+1, self.x+1, self.joint_name)
54 
55  if self.temperature == -1: # joint not found
56  self.screen.addstr(self.y + 1, self.x + 6, "X", curses.color_pair(4))
57  elif self.temperature < COOL:
58  self.screen.addstr(self.y + 1, self.x+6, str(self.temperature), curses.color_pair(1))
59  elif self.temperature < WARM:
60  self.screen.addstr(self.y + 1, self.x + 6, str(self.temperature), curses.color_pair(2))
61  else:
62  self.screen.addstr(self.y + 1, self.x + 6, str(self.temperature), curses.color_pair(3))
63  # self.window.refresh()#0,0,0,0,1,15)
64 
65 
66 class TemperatureMonitor(object):
67  MAX_X = 17
68  MAX_Y = 21
69 
70  def __init__(self, screen=None):
71  try:
72  curses.curs_set(0)
73  except:
74  pass
75  self.screen = screen
76  self.pad = curses.newpad(self.MAX_Y, self.MAX_X)
77  self.pad_pos_x_ = 0
78  self.pad_pos_y_ = 0
79  self.pad.border(0)
80  self.joint_monitors = {}
81 
82  curses.init_pair(4, curses.COLOR_WHITE, curses.COLOR_BLACK)
83  curses.init_pair(1, curses.COLOR_BLACK, curses.COLOR_GREEN)
84  curses.init_pair(2, curses.COLOR_BLACK, curses.COLOR_YELLOW)
85  curses.init_pair(3, curses.COLOR_BLACK, curses.COLOR_RED)
86 
87  for index, joint_name in enumerate(JOINT_NAMES):
88  begin_x = 0
89  begin_y = CASE_HEIGHT*index
90 
91  self.joint_monitors[joint_name] = Joint(self.pad, joint_name, begin_x, begin_y)
92 
93  self.diag_sub_ = rospy.Subscriber("/diagnostics", DiagnosticArray, self.diag_cb_)
94  self.resize_()
95 
96  while True:
97  event = self.pad.getch()
98  if event == ord("q"):
99  break
100  elif event == curses.KEY_RESIZE:
101  self.resize_()
102 
103  elif event == ord("s"):
104  self.pad_pos_y_ += 1
105  self.refresh_()
106  elif event == ord("w"):
107  self.pad_pos_y_ -= 1
108  self.refresh_()
109  elif event == ord("a"):
110  self.pad_pos_x_ -= 1
111  self.refresh_()
112  elif event == ord("d"):
113  self.pad_pos_x_ += 1
114  self.refresh_()
115 
116  def diag_cb_(self, msg):
117  for status in msg.status:
118  for joint in JOINT_NAMES:
119  if joint in status.name:
120  for value in status.values:
121  if value.key == "Temperature":
122  self.joint_monitors[joint].set_temperature(round(float(value.value), 1))
123  break
124  break
125  self.resize_()
126 
127  def resize_(self):
128  self.pad_pos_x_ = 0
129  self.pad_pos_y_ = 0
130  self.refresh_()
131 
132  def refresh_(self):
133  y, x = self.screen.getmaxyx()
134  self.pad_pos_x_ = min(max(self.pad_pos_x_, 0), self.MAX_X - 1)
135  self.pad_pos_y_ = min(max(self.pad_pos_y_, 0), self.MAX_Y - 1)
136  self.pad.refresh(self.pad_pos_y_, self.pad_pos_x_, 0, 0, y - 1, x - 1)
137  self.pad.border(0)
138  for monitor in self.joint_monitors.values():
139  monitor.refresh()
140 
141 
142 if __name__ == '__main__':
143  rospy.init_node("temperature_monitor", anonymous=True)
144  try:
145  curses.wrapper(TemperatureMonitor)
146  except:
147  traceback.print_exc()
def __init__(self, screen, joint_name, x, y)
def set_temperature(self, temperature)


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:49