Hi @thomas,
I createad a custom ai_segmentation_t
struct as
#define MASK_HEIGHT 480
#define MASK_WIDTH 640
typedef struct ai_segmentation_t
{
uint32_t magic_number;
int64_t timestamp_ns;
uint32_t class_id;
int32_t frame_id;
char class_name[BUF_LEN];
char cam[BUF_LEN];
bool first_segmentation;
bool last_segmentation;
float class_confidence;
float detection_confidence;
float x_min;
float y_min;
float x_max;
float y_max;
int8_t mask[MASK_HEIGHT * MASK_WIDTH]; // 2D array for segmentation mask
} __attribute__((packed)) ai_segmentation_t;
which are then written down to the pipe as (main.cpp file of the voxl-tflite-server)
std::vector<ai_segmentation_t> detections;
if (!inf_helper->postprocess_seg(output_image, detections, last_inference_time))
continue;
if (!detections.empty())
{
for (unsigned int i = 0; i < detections.size(); i++)
{
pipe_server_write(DETECTION_CH, (char *)&detections[i], sizeof(ai_segmentation_t));
}
}
new_frame->metadata.timestamp_ns = rc_nanos_monotonic_time();
pipe_server_write_camera_frame(IMAGE_CH, new_frame->metadata, (char *)output_image.data);
}
And retrieved by the ai_detection_interface.h in the callback function of voxl-mpa-to-ros
static void _helper_cb(__attribute__((unused)) int ch, char *data, int bytes, void *context)
{
AiDetectionInterface *interface = (AiDetectionInterface *)context;
if (interface->GetState() != ST_RUNNING)
return;
ros::Publisher &publisher = interface->GetPublisher();
voxl_mpa_to_ros::AiSegmentation &obj = interface->GetSegMsg();
std::vector<voxl_mpa_to_ros::AiSegmentation> obj_array;
voxl_mpa_to_ros::AiSegmentationArray obj_arrayMsg;
int n_packets = bytes / sizeof(ai_segmentation_t);
ai_segmentation_t *detections = (ai_segmentation_t *)data;
bool first_segmentation = false;
bool last_segmentation = false;
for (int i = 0; i < n_packets; i++)
{
if (detections[i].magic_number != AI_DETECTION_MAGIC_NUMBER)
return;
// publish the sample
obj.timestamp_ns = detections[i].timestamp_ns;
obj.class_id = detections[i].class_id;
obj.frame_id = detections[i].frame_id;
obj.class_name = detections[i].class_name;
obj.cam = detections[i].cam;
obj.class_confidence = detections[i].class_confidence;
obj.detection_confidence = detections[i].detection_confidence;
obj.x_min = detections[i].x_min;
obj.y_min = detections[i].y_min;
obj.x_max = detections[i].x_max;
obj.y_max = detections[i].y_max;
obj.first_segmentation = detections[i].first_segmentation;
obj.last_segmentation = detections[i].last_segmentation;
if (detections[i].first_segmentation)
{
first_segmentation = true;
}
if (detections[i].last_segmentation)
{
last_segmentation = true;
}
last_segmentation = true;
first_segmentation = true;
obj.mask = std::vector<int8_t>(detections[i].mask, detections[i].mask + sizeof(detections[i].mask) / sizeof(detections[i].mask[0]));
// add the
obj_array.push_back(obj);
}
obj_arrayMsg.segmentation_array = obj_array;
if (n_packets > 0 && publisher.getNumSubscribers() > 0 && first_segmentation && last_segmentation)
{
publisher.publish(obj_arrayMsg);
}
return;
}
and inside the ai_detection_interface has the ai_segmentation and ai_segmentation_array defined as (same as the tflite-server):
typedef struct ai_segmentation_t
{
uint32_t magic_number;
int64_t timestamp_ns;
uint32_t class_id;
int32_t frame_id;
char class_name[BUF_LEN];
char cam[BUF_LEN];
bool first_segmentation;
bool last_segmentation;
float class_confidence;
float detection_confidence;
float x_min;
float y_min;
float x_max;
float y_max;
int8_t mask[MASK_HEIGHT * MASK_WIDTH]; // 2D array for segmentation mask
} __attribute__((packed)) ai_segmentation_t;
typedef struct ai_array_segmentation_t {
std::vector<ai_segmentation_t> segmentations;
} __attribute__((packed)) ai_array_segmentation_t;
The problem is that the model runs and the output of the detection makes sense :
The usage of the GPU is:
[Name Freq (MHz) Temp (C) Util (%)
-----------------------------------
cpu0 1075.2 67.1 33.30
cpu1 1075.2 65.5 26.08
cpu2 1075.2 65.9 26.77
cpu3 1075.2 65.9 26.34
cpu4 710.4 67.1 16.08
cpu5 710.4 65.5 25.00
cpu6 710.4 65.5 23.67
cpu7 844.8 67.1 6.61
Total 67.1 22.98
10s avg 22.78
-----------------------------------
GPU 587.0 67.1 97.92
GPU 10s avg 49.08
-----------------------------------
memory temp: 65.0 C
memory used: 1125/7671 MB
-----------------------------------
Flags
CPU freq scaling mode: auto
Standby Not Active
-----------------------------------]
However, when I attempt to retrieve the segmentation from the voxl-mpa-to-ros the voxl2 reboot, even though some messages are received. While I might expect a crash at the code level or a segmentation fault, a total reboot occurs, which can create a few problems, especially when flying.
Also even tought it occurs more sporadically, the voxl2 also reboot by simply running the model and displaying on the portal the segmentations. However the voxl-inspect-cpu does not complain about overheating neither I notice any extra memory usage.
Any help is welcome!