Module: centerRadiusCNN

Executive Summary

This module implements any convolutional neural for image processing. More precisely, the module uploads a trained model and reads it using the OpenCV library. This module is then used on an image in order to extract a radius and center.

Module Assumptions and Limitations

The module’s assumptions are limited to the model it uploads. The training and performance of this module is not protected by this implementation. This assumption is seen in the pixelNoise variable where the user sets the performance of the net.

Message Connection Descriptions

The following table lists all the module input and output messages. The module msg variable name is set by the user from python. The msg type contains a link to the message structure definition, while the description provides information on what this message is used for.

Module I/O Messages

Msg Variable Name

Msg Type

Description

imageInMsg

CameraImageMsgPayload

(optional) Input image message. This message either comes from the camera module or the viz interface if no noise is added.

opnavCirclesOutMsg

OpNavCirclesMsgPayload

Circle found in the image.

User Guide

The module is set easily using the path to the module and message names:

1moduleConfig.pathToNetwork = path + "/../position_net2_trained_11-14.onnx"
2moduleConfig.pixelNoise = [5,5,5]

class CenterRadiusCNN : public SysModel
#include <centerRadiusCNN.h>

The CNN based center radius visual tracking module.

Public Functions

CenterRadiusCNN()

The constructor for the CenterRadiusCNN module. It also sets some default values at its creation.

~CenterRadiusCNN()

This is the destructor

void UpdateState(uint64_t CurrentSimNanos)

This module reads an OpNav image and extracts circle information from its content using OpenCV’s HoughCircle Transform. It performs a greyscale, a bur, and a threshold on the image to facilitate circle-finding.

Parameters:

CurrentSimNanos – The clock time at which the function was called (nanoseconds)

Returns:

void

void Reset(uint64_t CurrentSimNanos)

This method performs a complete reset of the module. Local module variables that retain time varying states between function calls are reset to their default values.

Parameters:

CurrentSimNanos – The clock time at which the function was called (nanoseconds)

Returns:

void

Public Members

std::string filename

Filename for module to read an image directly.

Message<OpNavCirclesMsgPayload> opnavCirclesOutMsg

The name of the OpNavCirclesMsg output message.

ReadFunctor<CameraImageMsgPayload> imageInMsg

The name of the camera output message.

std::string pathToNetwork

Path to the trained CNN.

uint64_t sensorTimeTag

[ns] Current time tag for sensor out

int32_t saveImages

[-] 1 to save images to file for debugging

double pixelNoise[3]

[-] Pixel Noise for the estimate

BSKLogger bskLogger

&#8212; BSK Logging

Private Members

cv::dnn::Net positionNet2

Network for evaluation of centers.