Class StParameter

Class Documentation

class StParameter

Class to handle ROS parameter.

This class reads camera list parameter.

Public Functions

StParameter()

Constructor.

virtual ~StParameter()

Destructor.

void loadCameraList(const rclcpp::Node *nh, std::vector<std::string> &camera_to_connect)

Load the camera list.

This function retrieves data from parameter camera_to_connect as a list of allowed camera to connect. The data is kept in variable vec_camera_to_connect_. If there is a special keyword ‘all’ among the data, the node will attempt to connect to any detected camera. If the parameter does not exist or there is no data, the node will only connect to the first found camera.

Parameters:
  • nh[in] Node handle of the main node.

  • camera_to_connect[out] Store the retrieved data excluding the special keyword ‘all’.

bool connectFirstCameraOnly() const

Check if the node shall connect to only the first found camera.

This function checks if the node shall connect to only the first found camera.

Returns:

True if connect to only the first found camera. False otherwise.

bool connectAllCamera() const

Check if the node shall connect to all detected camera.

This function checks if the node shall connect all detected camera.

Returns:

True if connect to all detected camera. False otherwise.

std::string getNamespace(std::string device_id) const

Obtain the namespace of the given camera identifier.

This function replaces any puctuation in the given camera identifier, which can be in the form of camera ID or MODEL(SERIAL), with under- score ‘_’, so that it complies with ROS namespace.

Parameters:

device_id[in] The camera identifier.

Returns:

The namespace of the camera.

rclcpp::Logger::Level getLoggerLevel(const rclcpp::Node *nh) const

Get logger level parameter.

This function will search for the logger_level parameter for the given camera namespace. If such parameter does not exist, rclcpp::Logger::Level::Info is returned.

Parameters:

nh[in] Node handle of the main node.

Returns:

Logger level.

Protected Attributes

std::vector<std::string> vec_camera_to_connect_

Store the list of allowed camera to connect, including special key- word ‘all’ if specified.