44 std::vector<std::string> &camera_to_connect)
47 camera_to_connect.clear();
49 if (nh.
hasParam(
"camera_to_connect"))
57 if (camera_id.compare(
"all") == 0)
63 camera_to_connect.push_back(camera_id);
68 std::string camera_namespace)
70 std::string param_key =
"";
71 if (!camera_namespace.empty())
75 std::string value =
"";
81 if (nh.
searchParam(
"default_calibration_file", param_key))
83 std::string value =
"";
100 if (value.compare(
"all") == 0)
return true;
107 std::replace_if(camera_id.begin(), camera_id.end(), ::ispunct,
'_');
108 return std::string(
"dev_" + camera_id);
std::vector< std::string > vec_camera_to_connect_
std::string getCalibrationFile(const ros::NodeHandle &nh, std::string camera_namespace)
bool searchParam(const std::string &key, std::string &result) const
bool connectFirstCameraOnly()
void loadCameraList(const ros::NodeHandle &nh, std::vector< std::string > &camera_to_connect)
std::string getNamespace(std::string camera_id)
bool getParam(const std::string &key, std::string &s) const
Class to handle ROS parameter.
bool hasParam(const std::string &key) const