Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bms UI feedback #161

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,3 +1,19 @@
<p>power-page works!</p>
<div>{{Results}}</div>
<input type="text" [(ngModel)]=Results>
<div class="power-feedback">
<p>Power Component</p>
<!-- Preview content before sent -->
<div class="cell-voltage">
<p>Cell Voltage: {{cellVoltage}}</p>
</div>
<div class="total-voltage">
<p>Total Voltage: {{totalVoltage}}</p>
</div>
<div class="charging-mosfet">
<p>Charging Mosfet: {{chargingMosfet}}</p>
</div>
<div class="discharging-mosfet">
<p>Discharging Mosfet: {{dischargingMosfet}}</p>
</div>
<div class="error-logs">
<p>Error Logs: {errorLogs}</p>
</div>
</div>
Original file line number Diff line number Diff line change
Expand Up @@ -11,45 +11,32 @@ import { RosService } from 'src/app/ros.service';
export class PowerPageComponent {
rosBridgeStatus: string;
ros: ROSLIB.Ros;
String: ROSLIB.Topic; //payload type
Pub: ROSLIB.Topic; //payload type

Results: string;

bmsData: ROSLIB.Topic; //payload type
errorLogs: string[];
cellVoltage: number[];
totalVoltage: number;
chargingMosfet: number;
dischargingMosfet: number;

constructor(private rosService: RosService) {
this.ros = this.rosService.getRos();
}

ngOnInit() {

this.String = new ROSLIB.Topic({
ros : this.ros,
name : '/chatter',
messageType : 'std_msgs/String'
this.bmsData= new ROSLIB.Topic({
ros: this.ros,
name: '/bmsData',
messageType: 'bms_feedback/BMSData'
});

this.Pub = new ROSLIB.Topic({
ros : this.ros,
name : 'lol',
messageType : 'std_msgs/String'
this.bmsData.subscribe((message:any) => {
console.log(message.cell_voltages);
this.cellVoltage = message.cell_voltages;
this.totalVoltage = message.total_voltage;
this.chargingMosfet = message.charging_mosfet;
this.dischargingMosfet = message.discharging_logs;
this.errorLogs = message.error_logs;
});

this.listen()
}

publish() {
this.Pub.publish({data:"YYOYOYY"+this.Results});
}

listen() {
this.String.subscribe((message:any) => {
// console.log('Received message on ' +this.listener.name + ': ' + message.y + message.x);
this.Results = ('Received message on ' + this.String.name +"and the message.data"+ message.data);
this.publish();
});
}



}

}
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,5 @@
<app-gps/>
</div>
<app-drive-component/>
<app-power-page/>
</div>
Binary file added bms_feedback/.DS_Store
Binary file not shown.
41 changes: 41 additions & 0 deletions bms_feedback/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
cmake_minimum_required(VERSION 3.0.2)
project(bms_feedback)


## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)

catkin_python_setup()

add_message_files(
FILES
BMSData.msg
)

generate_messages(
DEPENDENCIES
std_msgs
)



catkin_package(
CATKIN_DEPENDS
roscpp
rospy
std_msgs
LIBRARIES bms_feedback
CATKIN_DEPENDS message_runtime
)

catkin_install_python(PROGRAMS
src/bms_node.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
9 changes: 9 additions & 0 deletions bms_feedback/launch/bms_feedback.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<!-- Node for the UI -->
<node pkg="ui_app" type="main.py" name="ui" output="screen">
</node>

<!-- Node for the science embedded system -->
<node pkg="rosserial_python" type="serial_node.py" name="science_embedded" args="/dev/ttyACM0" ></node>

</launch>
8 changes: 8 additions & 0 deletions bms_feedback/msg/BMSData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
float32 total_voltage
float32 current
float32 soc_percent
float32[] cell_voltages
int8 charging_mosfet
int8 discharging_mosfet
float32 capacity_ah
string[] error_strings
30 changes: 30 additions & 0 deletions bms_feedback/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<?xml version="1.0"?>
<package format="2">
<name>bms_feedback</name>
<version>0.0.0</version>
<description>The science_module package</description>

<maintainer email="[email protected]">Vincent Boucher</maintainer>

<license>MIT</license>

<author email="[email protected]">Vincent Boucher</author>

<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>

<export>

</export>
</package>
12 changes: 12 additions & 0 deletions bms_feedback/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['bms_feedback'],
package_dir={'': 'src'},
)

setup(**setup_args)
81 changes: 81 additions & 0 deletions bms_feedback/src/bms_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
import os, sys
currentdir = os.path.dirname(os.path.realpath(__file__))
sys.path.append(currentdir)
import rospy
from bms_feedback.msg import BMSData
import dalybms

class BMSNode():

def __init__(self, device = "/dev/ttyACM0") -> None:


rospy.init_node("bms_feedback", anonymous=False)

self.bms_data_publisher = rospy.Publisher("bmsData", BMSData, queue_size=10)

self.device = device
self.bms_obj = dalybms.DalyBMS()
self.bms_obj.connect(self.device)
self.bmsData = BMSData()
self.bmsData.cell_voltages = [0 for x in range(1000)]

self.bms_errors = []
self.connected = self.bms_obj.serial.is_open

self.rate = rospy.Rate(1)

self.run()

def disconnect(self) -> None:
self.bms_obj.disconnect()
self.connected = False

def connect(self) -> bool:
self.bms_obj.connect(self.device)
self.connected = self.bms_obj.serial.is_open
return self.connected

def isConnected(self) -> bool:
return self.connected

def run(self) -> None:
while not rospy.is_shutdown():

self.getBMSData()

self.bms_data_publisher.publish(self.bmsData)

self.rate.sleep()


def getBMSData(self):
cell_voltages = self.bms_obj.get_cell_voltages()
soc_data = self.bms_obj.get_soc()
mosfet_status = self.bms_obj.get_mosfet_status()
self.bmsData.error_strings = self.bms_obj.get_errors()

if cell_voltages:
self.bmsData.cell_voltages[0] = cell_voltages["1"]
self.bmsData.cell_voltages[1] = cell_voltages["2"]
self.bmsData.cell_voltages[2] = cell_voltages["3"]
self.bmsData.cell_voltages[3] = cell_voltages["4"]
self.bmsData.cell_voltages[4] = cell_voltages["5"]
self.bmsData.cell_voltages[5] = cell_voltages["6"]
self.bmsData.cell_voltages[6] = cell_voltages["7"]
self.bmsData.cell_voltages[7] = cell_voltages["8"]


if soc_data:
self.bmsData.discharging_mosfet = int(mosfet_status["discharging_mosfet"])
self.bmsData.charging_mosfet = int(mosfet_status["charging_mosfet"])
self.bmsData.capacity_ah = mosfet_status["capacity_ah"]

if mosfet_status:
self.bmsData.total_voltage = soc_data["total_voltage"]
self.bmsData.current = soc_data["current"]
self.bmsData.soc_percent = soc_data["soc_percent"]

if __name__ == "__main__":
driver = BMSNode()
rospy.spin()
Loading