Skip to content

Commit

Permalink
pretty and add update map
Browse files Browse the repository at this point in the history
  • Loading branch information
xiaoqiang committed May 2, 2018
1 parent b906dc1 commit 6df2bc6
Show file tree
Hide file tree
Showing 12 changed files with 904 additions and 784 deletions.
11 changes: 11 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
# system_monitor
xiaoqiang system monitor. This program publishs current status of xiaoqiang to ```/system_monitor/report```. It also monitors the voltage of battery, and shutdown the system when battery is low.


Made with :heart: by BlueWhale Tech corp.


小强系统监控程序。这个程序把小强的当前状态发布到```/system_monitor/report``` topic中。同时此程序还会监控电池的电压,如果电压过低就会自动关闭整个系统。


由蓝鲸科技精 :heart: 制作。
79 changes: 43 additions & 36 deletions broadcast.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#!/usr/bin/env python
#coding:utf-8
# coding:utf-8

import rospy
from std_msgs.msg import String, UInt32, Float64, Bool
Expand All @@ -13,10 +13,10 @@
from socket import *
import commands

HOST = ''#should not be 127.0.0.1 or localhost
UserSocket_port=20001 #局域网udp命令监听端口
UserSocket_remote=None
UserSerSocket=None;
HOST = '' # should not be 127.0.0.1 or localhost
UserSocket_port = 20001 # 局域网udp命令监听端口
UserSocket_remote = None
UserSerSocket = None
BUFSIZE = 1024

PACKAGE_HEADER = [205, 235, 215]
Expand All @@ -37,22 +37,24 @@

dataCache = []


def getDataFromReq(req):
pass


def unpackReq(req):
global dataCache
res = []
packageList = splitReq(req)
# process the first package
completeData = dataCache + packageList[0]
packageList.remove(packageList[0])
packageList = splitReq(completeData) + packageList
packageList = splitReq(completeData) + packageList

for count in range(0, len(packageList)):
if len(packageList[count]) != 0 and len(packageList[count]) == packageList[count][0] + 1:
res.append(packageList[count][1:])
lastOne = packageList[-1:][0] # the last one
lastOne = packageList[-1:][0] # the last one
if len(lastOne) == 0 or len(lastOne) != lastOne[0] + 1:
dataCache = lastOne
return res
Expand All @@ -66,6 +68,7 @@ def findPackageHeader(req):
return count
return -1


def splitReq(req):
res = []
startIndex = 0
Expand All @@ -79,11 +82,12 @@ def splitReq(req):
res.append(req[startIndex:])
return res


def parseData(cmds):
res = None
for count in range(0, len(cmds)):
#判断是否为关机命令
if cmds[count][0]==0xaa and cmds[count][1]==0x44:
# 判断是否为关机命令
if cmds[count][0] == 0xaa and cmds[count][1] == 0x44:
print "system poweroff"
status, output = commands.getstatusoutput('sudo shutdown -h now')
# cmds[count][0] 为目标编号,取值为0到127
Expand All @@ -93,51 +97,53 @@ def parseData(cmds):
# todo 发布目标编号
# todo 发布目标编号




#only for debug
print "TargetNum %d" %(cmds[count][0])
print "MoveSpeed %d" %(cmds[count][1])
# only for debug
print "TargetNum %d" % (cmds[count][0])
print "MoveSpeed %d" % (cmds[count][1])
return res


class UserSer(threading.Thread):
#接收udp命令的socket
# 接收udp命令的socket
def __init__(self):
global HOST,CarSocket_port,UserSocket_port,CarSocket_remote,UserSocket_remote,CarSerSocket,UserSerSocket,BUFSIZE
global HOST, CarSocket_port, UserSocket_port, CarSocket_remote, UserSocket_remote, CarSerSocket, UserSerSocket, BUFSIZE
super(UserSer, self).__init__()
self._stop = threading.Event()
UserSerSocket=socket(AF_INET, SOCK_DGRAM)
UserSerSocket.bind((HOST,UserSocket_port))
UserSerSocket = socket(AF_INET, SOCK_DGRAM)
UserSerSocket.bind((HOST, UserSocket_port))

def stop(self):
global HOST,CarSocket_port,UserSocket_port,CarSocket_remote,UserSocket_remote,CarSerSocket,UserSerSocket,BUFSIZE
if UserSerSocket!=None:
global HOST, CarSocket_port, UserSocket_port, CarSocket_remote, UserSocket_remote, CarSerSocket, UserSerSocket, BUFSIZE
if UserSerSocket != None:
UserSerSocket.close()
self._stop.set()

def stopped(self):
global HOST,CarSocket_port,UserSocket_port,CarSocket_remote,UserSocket_remote,CarSerSocket,UserSerSocket,BUFSIZE
global HOST, CarSocket_port, UserSocket_port, CarSocket_remote, UserSocket_remote, CarSerSocket, UserSerSocket, BUFSIZE
return self._stop.isSet()

def run(self):
global HOST,CarSocket_port,UserSocket_port,CarSocket_remote,UserSocket_remote,CarSerSocket,UserSerSocket,BUFSIZE
global HOST, CarSocket_port, UserSocket_port, CarSocket_remote, UserSocket_remote, CarSerSocket, UserSerSocket, BUFSIZE
while not self.stopped() and not rospy.is_shutdown():
data, UserSocket_remote = UserSerSocket.recvfrom(BUFSIZE)
#print "UserSocket get data"
if not data: break
#rospy.loginfo(data)
if not data:
break
# rospy.loginfo(data)
dataList = []
for c in data:
dataList.append(ord(c))
parseData(unpackReq(dataList)) ##处理命令数据
self.stop();
parseData(unpackReq(dataList)) # 处理命令数据
self.stop()


def getPower(power):
mStatusLock.acquire()
mStatus.power = power.data
#if power.data < powerLow and not os.path.isfile(powerFlagFilePath) and power.data > 0.1:
# if power.data < powerLow and not os.path.isfile(powerFlagFilePath) and power.data > 0.1:
mStatusLock.release()


def getOrbTrackingFlag(cam_pose):
mStatusLock.acquire()
if cam_pose != None:
Expand All @@ -146,6 +152,7 @@ def getOrbTrackingFlag(cam_pose):
mStatus.orbInitStatus = False
mStatusLock.release()


def broadcast():
global reportPub
rospy.init_node("broadcast", anonymous=True)
Expand All @@ -156,27 +163,27 @@ def broadcast():
if __name__ == "__main__":
broadcast()
rate = rospy.Rate(1)
#配置udp广播
MYPORT = 22001 #广播端口
# 配置udp广播
MYPORT = 22001 # 广播端口
s = socket(AF_INET, SOCK_DGRAM)
s.bind(('', 0))
s.setsockopt(SOL_SOCKET, SO_BROADCAST, 1)
#开启udp接收监听线程
# 开启udp接收监听线程
UserSerThread = UserSer()
UserSerThread.start()
while not rospy.is_shutdown():

#每秒广播一次电压和ORB_SLAM tracker 状态
# 每秒广播一次电压和ORB_SLAM tracker 状态
if(mStatus.orbInitStatus):
data = "xq%5.2f1" % mStatus.power
else:
data = "xq%5.2f0" % mStatus.power
#发送广播包
# 发送广播包
s.sendto(data, ('<broadcast>', MYPORT))

#持续反馈状态
if UserSocket_remote!=None and UserSerSocket!=None:
UserSerSocket.sendto(data,UserSocket_remote)
# 持续反馈状态
if UserSocket_remote != None and UserSerSocket != None:
UserSerSocket.sendto(data, UserSocket_remote)

# clear data
mStatus.power = 0.0
Expand Down
35 changes: 21 additions & 14 deletions monitor.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,15 @@
powerLow = 9.8

mStatusLock = threading.Lock()
power_last=0
power_last = 0


def getBrightness(brightness):
mStatusLock.acquire()
mStatus.brightness = brightness.data
mStatusLock.release()


def getImage(image):
mStatusLock.acquire()
if image != None:
Expand All @@ -43,25 +45,28 @@ def getImage(image):
mStatus.imageStatus = False
mStatusLock.release()


def getPower(power):
global power_last,lower_nums
global power_last, lower_nums

mStatusLock.acquire()
if mStatus.power<0.1:
power_last=power.data
if power_last< power.data+0.7 and power_last> power.data-0.7:
if mStatus.power < 0.1:
power_last = power.data
if power_last < power.data + 0.7 and power_last > power.data - 0.7:
mStatus.power = power.data
if power.data < powerLow and power.data > 12.0: #and not os.path.isfile(powerFlagFilePath)
# and not os.path.isfile(powerFlagFilePath)
if power.data < powerLow and power.data > 12.0:
#flagFile = open(powerFlagFilePath, "w+")
#flagFile.write(str(power.data))
#flagFile.close()
lower_nums+=1
# flagFile.write(str(power.data))
# flagFile.close()
lower_nums += 1
# if lower_nums>100:
# status, output = commands.getstatusoutput('sudo shutdown -h now')
lower_nums=0
power_last=power.data
lower_nums = 0
power_last = power.data
mStatusLock.release()


def getOdom(odom):
mStatusLock.acquire()
if odom != None:
Expand All @@ -70,6 +75,7 @@ def getOdom(odom):
mStatus.odomStatus = False
mStatusLock.release()


def getOrbStartStatus(orb_frame):
mStatusLock.acquire()
if orb_frame != None:
Expand All @@ -78,6 +84,7 @@ def getOrbStartStatus(orb_frame):
mStatus.orbStartStatus = False
mStatusLock.release()


def getOrbTrackingFlag(cam_pose):
mStatusLock.acquire()
if cam_pose != None:
Expand All @@ -86,6 +93,7 @@ def getOrbTrackingFlag(cam_pose):
mStatus.orbInitStatus = False
mStatusLock.release()


def getOrbScaleStatus(flag):
mStatusLock.acquire()
mStatus.orbScaleStatus = flag.data
Expand All @@ -102,8 +110,7 @@ def monitor():
rospy.Subscriber("/xqserial_server/Odom", Odometry, getOdom)
rospy.Subscriber("/ORB_SLAM/Camera", Pose, getOrbTrackingFlag)
rospy.Subscriber("/orb_scale/scaleStatus", Bool, getOrbScaleStatus)
reportPub = rospy.Publisher('/system_monitor/report', Status , queue_size
=0)
reportPub = rospy.Publisher('/system_monitor/report', Status, queue_size=0)


if __name__ == "__main__":
Expand All @@ -112,7 +119,7 @@ def monitor():

while not rospy.is_shutdown():
mStatusLock.acquire()
if reportPub != "":
if reportPub != "":
reportPub.publish(mStatus)
# clear data
mStatus.brightness = 0
Expand Down
Loading

0 comments on commit 6df2bc6

Please sign in to comment.