Rosserial data section exceeds available space

asked 2021-12-27 03:34:56 -0500

Hi! I want to read in a VL53L0X Lidar with an Arduino Uno R3 and publish it on a topic using Rosserial. Here is my code:

#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>

#include "Adafruit_VL53L0X.h"


ros::NodeHandle  nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range( "range_data", &range_msg);
Adafruit_VL53L0X sensor = Adafruit_VL53L0X();
VL53L0X_RangingMeasurementData_t measure;

unsigned long range_timer;

void setup() {
  nh.initNode();
  nh.getHardware()->setBaud(57600);
  nh.advertise(pub_range);
  // wait controller to be connected
  while (!nh.connected()){
    nh.spinOnce();
  }
  // if initialization failed - write message and freeze
  if (!sensor.begin()) {
    //nh.logwarn("Failed to setup VL53L0X sensor");
    nh.logwarn("!");
    while(1);
  }
  nh.loginfo("VL53L0X API serial node started");
  // fill static range message fields
  range_msg.radiation_type = sensor_msgs::Range::INFRARED;
  range_msg.header.frame_id =  "ir_ranger";
  range_msg.field_of_view = 0.44; //25 degrees
  range_msg.min_range = 0.03;
  range_msg.max_range = 1.2;
}


void loop() {
  if ((millis()-range_timer) > 50){
    sensor.rangingTest(&measure, false);
    if (measure.RangeStatus != 4) {  // phase failures have incorrect data
        range_msg.range = (float)measure.RangeMilliMeter/1000.0f; // convert mm to m
        range_msg.header.stamp = nh.now();
        pub_range.publish(&range_msg);
    } else {
      nh.logwarn("Out of range"); // if out of range, don't send message
    }
    range_timer =  millis();    
  }
  nh.spinOnce();
}

The error message says:

Arduino: 1.8.16 (Linux), Board: "Arduino Uno"

Sketch uses 25860 bytes (80%) of program storage space. Maximum is 32256 bytes.
Global variables use 2502 bytes (122%) of dynamic memory, leaving -454 bytes for local variables. Maximum is 2048 bytes.
data section exceeds available space in board
Not enough memory; see https://support.arduino.cc/hc/en-us/articles/360013825179 for tips on reducing your footprint.
Error compiling for board Arduino Uno.

During my search I have already found out that you can reduce the maximum subscribers and publishers as well as the input and output size in node_handle.h. Unfortunately, this has not improved my problem.

Does anyone have any idea how I can get the Scetch to work?

edit retag flag offensive close merge delete