Class ProfilesManager

Inheritance Relationships

Derived Types

Class Documentation

class ProfilesManager

Subclassed by realsense2_camera::MotionProfilesManager, realsense2_camera::VideoProfilesManager

Public Functions

ProfilesManager(std::shared_ptr<Parameters> parameters, rclcpp::Logger logger)
virtual bool isWantedProfile(const rs2::stream_profile &profile) = 0
virtual void registerProfileParameters(std::vector<stream_profile> all_profiles, std::function<void()> update_sensor_func) = 0
bool isTypeExist()
void registerSensorQOSParam(std::string template_name, std::set<stream_index_pair> unique_sips, std::map<stream_index_pair, std::shared_ptr<std::string>> &params, std::string value)
template<class T>
void registerSensorUpdateParam(std::string template_name, std::set<stream_index_pair> unique_sips, std::map<stream_index_pair, std::shared_ptr<T>> &params, T value, std::function<void()> update_sensor_func)
void addWantedProfiles(std::vector<rs2::stream_profile> &wanted_profiles)
void clearParameters()
bool hasSIP(const stream_index_pair &sip) const
rmw_qos_profile_t getQOS(const stream_index_pair &sip) const
rmw_qos_profile_t getInfoQOS(const stream_index_pair &sip) const

Public Static Functions

static std::string profile_string(const rs2::stream_profile &profile)

Protected Functions

std::map<stream_index_pair, rs2::stream_profile> getDefaultProfiles()

Protected Attributes

rclcpp::Logger _logger
SensorParams _params
std::map<stream_index_pair, std::shared_ptr<bool>> _enabled_profiles
std::map<stream_index_pair, std::shared_ptr<std::string>> _profiles_image_qos_str
std::map<stream_index_pair, std::shared_ptr<std::string>> _profiles_info_qos_str
std::vector<rs2::stream_profile> _all_profiles
std::vector<std::string> _parameters_names