Solar Rovers - trying to run Ardupilot indefinitely

so the beaglebone blue is almost fully operational, running the latest ardupilot the only issue left is with the canbus GPS but I have just wired it in using serial and disconnected the RC telemetry for now.

I have updated the hoverboard controller code to fix its idle issues, basically I was mapping 1000-2000 directly to -100rpm to +100rpm, this worked fine when driving but the problem was I didn’t take into account any deadzone, so when it was stationary, if it wasn’t exactly on 1500 it would always want to move slightly. by adding a 20us deadzone it fixed that problem.

I have the SimpleFOC controllers working good enough that I’m going to install them, but since my solar rover is back outside, I’m going to install them onto my smaller urban rover for testing.
After some more digging I found that the simple FOC controllers I bought don’t have phase power measuring only total power, that’s not ideal, but I can still use it. The other issue I was having was getting the hall sensors to work. No matter what order I put them in, it was acting weird. I suspect the issue is trying to run the hall sensors on 3.3v, so I will probably need a logic level converter to get them to work. For now i have just been using the motors in sensorless mode and for what im going to be doing it’s probably going to be good enough. It just means if you overload them, then they will slip and take a second to restart rather than push all the way back to the original position.

The main thing I have been testing is the power consumption and the controllers way more efficient compared to the v1 hoverboard controllers especially at idle. It can hold all the wheels with only a couple of watts compared to the 20+ on the hoverboard controllers. with the ability to control the phase voltage in real time I’m going to make a basic algorithm that will boost torque in specific situations like turning on the spot then dropping down on low load for efficient driving. since its a esp32 it can also go into deep sleep when idle consuming only around 1mw.

I am still having issues with the LD06 lidar, I can find examples of it working in sunlight, but I get a lot of random interference when I try to use it outdoors, im currently working on some filtering that can compare every second scan to determine if there are any false readings.

void MAP_MAVLINK() {

  if (send = 0) {
    if (ld06.readScan()) {
      uint16_t n = ld06.getNbPointsInScan();  

      for (uint16_t i = 0; i < n; i++) {
        lidarAngle = ld06.getPoints(i)->angle;
        distances0[lidarAngle] = (ld06.getPoints(i)->distance / 10);
      }
      send = 1;
    }
  }

  if (send = 1) {
    if (ld06.readScan()) {
      uint16_t n = ld06.getNbPointsInScan();  

      for (uint16_t i = 0; i < n; i++) {
        lidarAngle = ld06.getPoints(i)->angle;
        distances1[lidarAngle] = (ld06.getPoints(i)->distance / 10);

        if (distances1[i] > (distances0[i] - 20) && distances1[i] < (distances1[i] + 20)) {
          messageAngle = map(lidarAngle, 0, 360, 0, 72);

          if (distances1[lidarAngle] < messageAngle && distances1[lidarAngle] > 5) {
            distances[messageAngle] = (ld06.getPoints(i)->distance / 10);
          }
        }
      }
      send = 0;

I have a new BMS library to test to get my bluetooth BMS to communicate with ardupilot, This library looks much more promising as it’s their app that I use on my phone for them. I still need to get ardupilot to use the mavlink battery data using this script.

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


void MAVLINK_BATTHB() {
  uint8_t autopilot_type = MAV_AUTOPILOT_INVALID;
  uint8_t system_mode = MAV_MODE_PREFLIGHT;  ///< Booting up
  uint32_t custom_mode = 0;                  ///< Custom mode, can be defined by user/adopter
  uint8_t system_state = MAV_STATE_STANDBY;  ///< System ready for flight
  mavlink_message_t msg;
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];
  int type = MAV_TYPE_GROUND_ROVER;
  // Pack the message

  mavlink_msg_heartbeat_pack(1, 180, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
  Serial1.write(buf, len);
}

void MAVBATTERY() {
  uint16_t CELLSA[10] = { CELLS[0], CELLS[1], CELLS[2], CELLS[3], CELLS[4], CELLS[5], CELLS[6], CELLS[7], CELLS[8], CELLS[9] };
  uint16_t CELLSB[4] = { CELLS[10], CELLS[11], CELLS[12], CELLS[13] };

  uint8_t system_id = 1;  // id of computer which is sending the command (ground control software has id of 255)
  uint8_t component_id = 180;
  mavlink_message_t msg;
  uint8_t id = 0;
  uint8_t battery_function = 2;  //propulsioni
  uint8_t type = 3;              //liion
  int16_t temperature = bms.get_ntc_temperature(1);
  uint16_t* voltages = CELLSA;
  int16_t current_battery = CURRENT;
  int32_t current_consumed = (20000 - CAPACITY);
  int32_t energy_consumed = 10000;
  int8_t battery_remaining = SOC;
  int32_t time_remaining = (CAPACITY / CURRENT);
  uint8_t charge_state = 1;
  uint16_t* voltages_ext = CELLSB;
  uint8_t mode = 0;
  uint32_t fault_bitmask = 0;


  //Pack battery message
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];
  mavlink_msg_battery_status_pack(system_id, component_id, &msg, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining, time_remaining, charge_state, voltages_ext, mode, fault_bitmask);
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);  // Send the message (.write sends as bytes)

  //if (CELLS[1] > 1) {
  Serial1.write(buf, len);  //Write data to serial port
  //}
}

progress!


https://www.aliexpress.com/item/1005006347440227.html