Class to handle ROS parameter. More...
#include <stparameter.h>
Public Member Functions | |
bool | connectAllCamera () |
bool | connectFirstCameraOnly () |
std::string | getCalibrationFile (const ros::NodeHandle &nh, std::string camera_namespace) |
std::string | getNamespace (std::string camera_id) |
void | loadCameraList (const ros::NodeHandle &nh, std::vector< std::string > &camera_to_connect) |
StParameter () | |
virtual | ~StParameter () |
Protected Attributes | |
std::vector< std::string > | vec_camera_to_connect_ |
Class to handle ROS parameter.
This class reads camera list parameter and path of calibration file.
Definition at line 51 of file stparameter.h.
stcamera::StParameter::StParameter | ( | ) |
Constructor.
Definition at line 35 of file stparameter.cpp.
|
virtual |
Destructor.
Definition at line 39 of file stparameter.cpp.
bool stcamera::StParameter::connectAllCamera | ( | ) |
Check if the node shall connect to all detected camera.
This function checks if the node shall connect all detected camera.
Definition at line 95 of file stparameter.cpp.
bool stcamera::StParameter::connectFirstCameraOnly | ( | ) |
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.
Definition at line 90 of file stparameter.cpp.
std::string stcamera::StParameter::getCalibrationFile | ( | const ros::NodeHandle & | nh, |
std::string | camera_namespace | ||
) |
Get calibration file for the given camera.
This function will search for the calibration_file parameter for the given camera namespace. If such parameter does not exist, the value of the default_calibration_file parameter will be used. In case that the parameter also does not exist, empty string is returned.
[in] | nh | Node handle of the camera. |
[in] | camera_namespace | The camera namespace. |
Definition at line 67 of file stparameter.cpp.
std::string stcamera::StParameter::getNamespace | ( | std::string | camera_id | ) |
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.
[in] | camera_id | The camera identifier. |
Definition at line 105 of file stparameter.cpp.
void stcamera::StParameter::loadCameraList | ( | const ros::NodeHandle & | 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.
[in] | nh | Node handle of the main node. |
[out] | camera_to_connect | Store the retrieved data excluding the special keyword 'all'. |
Definition at line 43 of file stparameter.cpp.
|
protected |
Store the list of allowed camera to connect, including special key- word 'all' if specified.
Definition at line 124 of file stparameter.h.