Set Battery Monitor voltage and current

I have a customized sensor that sends data containing voltage, current, temperature and rpm. I want my flight controller to use voltage and current as Battery Monitor.
Also I want to see temperature and rpm data in GCS.
We have companion computer that has a Mavlink connection to my flight controller.
Is there any way to do this using LUA scripting (or using Mavlink)?

I managed to do this by mixing Mavlink and LUA scripting.
I first receive data from my sensor in my companion computer and then send it using the Mavlink message “BATTERY_STATUS”. Then, in flight control, I receive this message using LUA scripting with the “receive_chan” method of “mavlink” and update the flight control’s battery data using the “update_telem_data” and “update_rpm” methods of “esc_telem” with received values.

3 Likes

can you share your script?

Which one of the scripts do you need?
Mavlink or LUA?

The just the Lua script, I can send the battery message from my esp32 I just can’t do anything with them.

local mavlink_msgs = require("mavlink/mavlink_msgs")
local msg_map = {}
local battery_status_msgid = mavlink_msgs.get_msgid("BATTERY_STATUS")
msg_map[battery_status_msgid] = "BATTERY_STATUS"


-- initialise mavlink rx with number of messages, and buffer depth
mavlink.init(1, 10)
-- register message id to receive
mavlink.register_rx_msgid(battery_status_msgid)


function update()
  local telem_data = ESCTelemetryData()

  local msg,_,timestamp_ms = mavlink.receive_chan()
  if msg then
    local parsed_msg = mavlink_msgs.decode(msg, msg_map)
      if(parsed_msg.msgid ~= nil and parsed_msg.msgid == battery_status_msgid) then

        telem_data:voltage((parsed_msg.voltages[0] or parsed_msg.voltages[1]) / 100)
        telem_data:temperature_cdeg(parsed_msg.temperature)
        telem_data:current(parsed_msg.current_consumed / 1000)
        esc_telem:update_telem_data(1, telem_data, 0x0D)

      end

  end
  return update, 1000
end

return update, 1000

This is the LUA script to do that.

1 Like

How do you set up the flight controller to use it?? Do I need to change batt settings?

As I remember I just set BATT_MONITOR. Did you test that without setting any more specific parameters?

What did you set the batt monitor to? What kind of sensor.

If I’m right I set BATTx_MONITOR = 9(ESC)

1 Like

Hii @Zeinab_Jalali, Can you please explain the process of the things that you did for the battery monitor to get all the parameter values from mavlink messages?

Hey I’m trying something similar to your mentioned problem statement. Can i get the Mavlink script which will send the voltage, current and temperature values via mavlink message. Currently Im trying to send i2c data through an Arduino controller. I have used the Mavlink library and used the mavlink_msg_battery_status_pack function to send the BMS data via mavlink message. I’m able to see the 6S battery - per cell voltage data on the mavlink inspector via mavlink monitor in the battery_status directory in QGC.

The similar cannot be said with the individual cell voltage in Mission planner. I only get the data from first voltage, skipping the voltage, current and temperature data from rest 5 cells and it does not show the full battery capacity as it does not add up the voltage data of each cell. I want your help regarding this. I have attached the Arduino script below, please go through it.
2_Arduino_mavlink_msg.zip (1.6 KB)

Hi,
I connected a companion computer (in my case, Jetson) to my sensor, read the sensor data in Jetson using serial, and then sent it in pymavlink using the battery_status mavlink message (master.mav. battery_status_send). Flight control, in my case, is connected to Jetson using a serial connection, and this process will send the mavlink message to flight control, but flight control cannot update values in this way.
Then I add a LUA script (which is available a few messages higher) to read that mavlink message and then update esc_telem data using the values read. You just need to set BATTx_MONITOR to 9 so that the config flight control updates battery data using ESC telemetry.

I used this code for sending mavlink message:


from pymavlink import mavutil
import os
import time

os.environ['MAVLINK20'] = '1'
os.environ['MAVLINK_DIALECT'] = 'ardupilotmega'

master = mavutil.mavlink_connection('/dev/ttyACM0', source_system = 1)

master.wait_heartbeat()

print("connected")

while(True):
	master.mav.battery_status_send(
				1,
				0,
				1,
				3000,
				[2200,65535,65535,65535,65535,65535,65535,65535,65535,65535],
				-1,
				3200,
				300,
				-1,
				0,
				6,
				[0,0,0,0],
				0,
				0)

	time.sleep(0.5)

I added all cell voltages and used this sum value in the first index of “voltages”. As mavlink document says, you can do this, but I cannot remember whether or not I used the format you used and what the result was. Do you have any requirements for sending a specific cell voltage?
And what I cannot understand in your case is how you want to send temperature and current for each cell? As I know, each battery monitor has temperature and current. And what mission data item did you use to monitor?

As I said earlier, by using the same mavlink protocol function (Battery_status) the mission planner does not show the correct combined voltage value of each individual cell in a 6S battery and it just displays the per cell voltage of the first single cell, It’s one of the problem when using the arduino mavlink library to display data through mission planner
Also that I am able to read all the data through Mavlink messages using the same library through the serial port using QGC.

Now that I want to skip the Arduino board and want to read the same battery data using the lua script or battery monitor drivers using the controller’s I2C ports, I’m confused between writing seperate battery monitor driver (Enabling the batt_monitor parameter as the new param value for bms smart battery let’s say 40) or lua scripts. I need help regarding this.

I tried writing a seperate driver in the libraries/ap_battmonitor directory, I referred the driver files already written for INA2XX and LTC2946 battery monitor as they use the I2C protocol for communication. I am currently using the BQ40Z80 I2C battery monitor which is identical to the SMBus battery monitor, I’m currently trying to debug it.

Summary of the message is that what will be more suitable to read the data from this BQ40Z80 Battery monitor from the Ardupilot as the Ardupilot will always prefer to act as Master and the BMS will act as a slave and send the data ??
i) Writing a seperate driver for BQ40Z80 battery monitor in ardupilot/ap_battmonitor directory (Here I will need controller probably to use it’s I2C ports for data)
ii) writing a lua script that will display the same data from BMS and display on GCS directly (here i don’t need flight controller as the changes are directly made into the firmware/autopilot)