[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

Package Summary

MPPT message sender package

MPPT ROS Package

Introduction

The aim of this package is to send splitted data from a MPPT device in ros. The package reads holding values from the MPPT, which are sent using ve-direct protocol via serial USB port.

Installation

From the distro repo

sudo apt-get install ros-kinetic-ros_mppt

From sources

Clone the package from github repo into your catkin workspace and build as usual

$ git clone https://github.com/AaronPB/ros_mppt.git

Customize the sender

Depending on the interested values from the serial communication interface, it is possible to define more values into the package.

MPPT Values:

Label

Units

Description

Type of variable

V

mV

Main (battery) voltage

Float

I

mA

Battery current

Float

VPV

mV

Panel voltage

Float

PPV

W

Panel power

Float

PID

Product ID

String

SER#

Serial Number

String

HSDS

Day sequence number (0 ... 364)

Int

MPPT

Tracker operation mode

Int

ERR

Error code

Int

CS

State of operation

Int

H19

0.01 kW/h

Yield Total (user resettable counter)

Float

H20

0.01 kW/h

Yield today

Float

H21

W

Maximum power today

Float

H22

0.01 kW/h

Yield yesterday

Float

H23

W

Maximum power yesterday

Float

Add the interested values into vemppt_ros

Choose those values you want to send from the topic, and modify the python file "vemppt_ros.py" adding them with this structure:

First, define the value where the other ones are already be defined:

   1 #Predefined values of msg
   2     msg.v_bat = -1
   3     msg.i_bat = -1
   4     msg.v_pv = -1
   5     msg.p_pv = -1

Then, add into the while loop the following lines of code:

   1 elif "V" in ve_read and "P" not in ve_read: #Filter
   2             try:
   3                 ve_read = ve_read.split("\t") #Splitter
   4                 msg.v_bat = float(ve_read[1]) * 0.001 #Value of splitted data
   5             except Exception as e: logging.error('Exception ocurred in V', exc_info=True) #Log info register in case of error

The first line is the filter, the "important filters" are already made so you only need to put the label of the value into a string (see the example).

The other line you have to care about, is the value of the splitted data. Define it following the MPPT values table.

Example

Imagine you want to see the error codes that the mppt is sending.

First, we define it in the predefined msg values section in vemppt_ros.py as msg.error_mppt:

   1 #Predefined values of msg
   2     msg.v_bat = -1
   3     msg.i_bat = -1
   4     msg.v_pv = -1
   5     msg.p_pv = -1
   6     msg.error_mppt = 0 #Let's say it has no error at the beginning

Then, we add the following lines of code into the while loop:

   1 elif "ERROR" in ve_read: #Filter with "ERROR" label
   2             try:
   3                 ve_read = ve_read.split("\t") #Splitter (nothing changed)
   4                 msg.error_mppt = int(ve_read[1]) #Value of splitted data (no operations needed, and defined as an integer)
   5             except Exception as e: logging.error('Exception ocurred in ERROR', exc_info=True) #Log info register in case of error ("V" modified to "ERROR")

The modified sender() method will looks like the following code:

   1 """
   2     This file is part of ros_mppt.
   3     ros_mppt is free software: you can redistribute it and/or modify
   4     it under the terms of the GNU General Public License as published by
   5     the Free Software Foundation, either version 3 of the License, or
   6     any later version.
   7     ros_mppt is distributed in the hope that it will be useful,
   8     but WITHOUT ANY WARRANTY; without even the implied warranty of
   9     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
  10     GNU General Public License for more details.
  11     You should have received a copy of the GNU General Public License
  12     along with ros_mppt.  If not, see <https://www.gnu.org/licenses/>.
  13 """
  14 
  15 def sender():
  16     pub = rospy.Publisher('mppt_channel', mppt, queue_size=10)
  17     rospy.init_node('ros_mppt', anonymous=True)
  18     r = rospy.Rate(10)
  19     msg = mppt()
  20 
  21     #Predefined values of msg
  22     msg.v_bat = -1
  23     msg.i_bat = -1
  24     msg.v_pv = -1
  25     msg.p_pv = -1
  26     msg.error_mppt = 0
  27 
  28     while not rospy.is_shutdown():
  29 
  30         try:
  31             ve_read = ser.readline().decode("utf-8")
  32         except: logging.warning('Skipping decoding from ve_read line: ' + ve_read)
  33 
  34         if "V" in ve_read and "P" not in ve_read:
  35             try:
  36                 ve_read = ve_read.split("\t")
  37                 msg.v_bat = float(ve_read[1]) * 0.001
  38             except Exception as e: logging.error('Exception ocurred in V', exc_info=True)
  39         elif "I" in ve_read and "P" not in ve_read:
  40             try:
  41                 ve_read = ve_read.split("\t")
  42                 msg.i_bat = float(ve_read[1]) * 0.001
  43             except Exception as e: logging.error('Exception ocurred in I', exc_info=True)
  44         elif "VPV" in ve_read:
  45             try
  46                 ve_read = ve_read.split("\t") * 0.001
  47                 msg.v_pv = float(ve_read[1])
  48             except Exception as e: logging.error('Exception ocurred in VPV', exc_info=True)
  49         elif "PPV" in ve_read:
  50             try:
  51                 ve_read = ve_read.split("\t")
  52                 msg.p_pv = float(ve_read[1])
  53             except Exception as e: logging.error('Exception ocurred in PPV', exc_info=True)
  54         #Our new mppt value
  55         elif "ERROR" in ve_read:
  56             try:
  57                 ve_read = ve_read.split("\t")
  58                 msg.error_mppt = int(ve_read[1])
  59             except Exception as e: logging.error('Exception ocurred in ERROR', exc_info=True)
  60 
  61         rospy.loginfo(msg)
  62         pub.publish(msg)
  63         r.sleep()

Now, we have our new custom value created. But, we need to do something else to send it to the topic: define it in the .msg file.

Add new values in the .msg file

If you want to add more custom values to the mppt_channel topic you have to defined those in the .msg file. Go to msg/mppt.msg in your catkin workspace and add the new custom values into them:

float64 v_bat
float64 i_bat
float64 v_pv
float64 p_pv

Following our previous example, we need to define msg.error_mppt into the mppt.msg file (as an integer):

float64 v_bat
float64 i_bat
float64 v_pv
float64 p_pv
int32 error_mppt

You can also define your own custom values just as state values or anything else. More info of .msg files at the Documentation section.

Run ros_mppt

To run the package first make sure to build it (also important if you made any changes at vemppt_ros.py):

$ cd ~/catkin_ws
$ catkin_make
$ . ~/catkin_ws/devel/setup.bash

Then, just run roscore and vemppt_ros.py:

$ rosrun roscore
$ rosrun ros_mppt vemppt_ros.py

If you want to save the topic, you can use the rosbag command:

$ rosbag -a

More info about ros commands at the Documentation section.

Documentation

GitHub Repositories

vemppt_reader MPPT data registration into a xls file for experimental purposes.

ros_mppt MPPT ROS package.

Victron Energy Documents

VE Direct Protocol

[PDF] VE.Direct Protocol VE.Direct Protocol - Version 3.25.

[PDF] BlueSolar HEX BlueSolar HEX protocol MPPT.

[WIKI] MPPT Solar Charger Error Codes

ROS Wiki Information

[WIKI] ROS MSG Formats

[WIKI] ROS CommandLineTools

[WIKI] ROS Basic Indications for packages


2024-03-16 12:56