vemppt_ros.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4  This file is part of ros_mppt.
5  ros_mppt is free software: you can redistribute it and/or modify
6  it under the terms of the GNU General Public License as published by
7  the Free Software Foundation, either version 3 of the License, or
8  any later version.
9  ros_mppt is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13  You should have received a copy of the GNU General Public License
14  along with ros_mppt. If not, see <https://www.gnu.org/licenses/>.
15 """
16 
17 
18 import rospy
19 import time
20 import serial
21 import logging
22 from ros_mppt.msg import mppt
23 
24 logging.basicConfig(level=logging.INFO, filename='ros_mppt.log', filemode='a', format='[%(asctime)s - %(levelname)s]: %(message)s', datefmt='%d-%b-%y %H:%M:%S')
25 logging.info('Initializing ros_mppt package...')
26 
27 def sender():
28  pub = rospy.Publisher('mppt_channel', mppt, queue_size=10)
29  rospy.init_node('ros_mppt', anonymous=True)
30  r = rospy.Rate(10)
31  msg = mppt()
32 
33  #Predefined values of msg
34  msg.v_bat = -1
35  msg.i_bat = -1
36  msg.v_pv = -1
37  msg.p_pv = -1
38 
39  while not rospy.is_shutdown():
40 
41  try:
42  ve_read = ser.readline().decode("utf-8")
43  except: logging.warning('Skipping decoding from ve_read line: ' + ve_read)
44 
45  if "V" in ve_read and "P" not in ve_read:
46  try:
47  ve_read = ve_read.split("\t")
48  msg.v_bat = float(ve_read[1]) * 0.001
49  except Exception as e: logging.error('Exception ocurred in V', exc_info=True)
50  elif "I" in ve_read and "P" not in ve_read:
51  try:
52  ve_read = ve_read.split("\t")
53  msg.i_bat = float(ve_read[1]) * 0.001
54  except Exception as e: logging.error('Exception ocurred in I', exc_info=True)
55  elif "VPV" in ve_read:
56  try
57  ve_read = ve_read.split("\t") * 0.001
58  msg.v_pv = float(ve_read[1])
59  except Exception as e: logging.error('Exception ocurred in VPV', exc_info=True)
60  elif "PPV" in ve_read:
61  try:
62  ve_read = ve_read.split("\t")
63  msg.p_pv = float(ve_read[1])
64  except Exception as e: logging.error('Exception ocurred in PPV', exc_info=True)
65 
66  rospy.loginfo(msg)
67  pub.publish(msg)
68  r.sleep()
69 
70 if __name__ == '__main__':
71  try:
72  ser = serial.Serial('/dev/ttyUSB0', 19200, timeout=10)
73  sender()
74  except rospy.ROSInterruptException: pass
75  finally:
76  ser.close()
def sender()
Definition: vemppt_ros.py:27


ros_mppt
Author(s): Aaron PB
autogenerated on Mon Sep 23 2019 03:29:11