Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support for selecting stream_type specific profile #3019

Closed
Closed
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@

#### with ros2 launch:
ros2 launch realsense2_camera rs_launch.py
ros2 launch realsense2_camera rs_launch.py depth_module.profile:=1280x720x30 pointcloud.enable:=true
ros2 launch realsense2_camera rs_launch.py depth_module.depth_profile:=1280x720x30 pointcloud.enable:=true

<hr>

Expand Down Expand Up @@ -251,10 +251,10 @@ User can set the camera name and camera namespace, to distinguish between camera
#### Parameters that can be modified during runtime:
- All of the filters and sensors inner parameters.
- Video Sensor Parameters: (```depth_module``` and ```rgb_camera```)
- They have, at least, the **profile** parameter.
- They have, at least, the **<stream_type>_profile** parameter.
- The profile parameter is a string of the following format: \<width>X\<height>X\<fps> (The dividing character can be X, x or ",". Spaces are ignored.)
- For example: ```depth_module.profile:=640x480x30 rgb_camera.profile:=1280x720x30```
- Since infra, infra1, infra2 and depth are all streams of the depth_module, their width, height and fps are defined by the same param **depth_module.profile**
- For example: ```depth_module.depth_profile:=640x480x30 depth_module.infra_profile:=640x480x30 rgb_camera.color_profile:=1280x720x30```
- Note: The param **depth_module.infra_profile** is common for all infra streams. i.e., infra 0, 1 & 2.
- If the specified combination of parameters is not available by the device, the default or previously set configuration will be used.
- Run ```ros2 param describe <your_node_name> <param_name>``` to get the list of supported profiles.
- Note: Should re-enable the stream for the change to take effect.
Expand Down
12 changes: 6 additions & 6 deletions realsense2_camera/include/profile_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,22 +68,22 @@ namespace realsense2_camera
VideoProfilesManager(std::shared_ptr<Parameters> parameters, const std::string& module_name, rclcpp::Logger logger, bool force_image_default_qos = false);
bool isWantedProfile(const rs2::stream_profile& profile) override;
void registerProfileParameters(std::vector<stream_profile> all_profiles, std::function<void()> update_sensor_func) override;
int getHeight() {return _height;};
int getWidth() {return _width;};
int getFPS() {return _fps;};
int getHeight(rs2_stream stream_type) {return _height[stream_type];};
int getWidth(rs2_stream stream_type) {return _width[stream_type];};
int getFPS(rs2_stream stream_type) {return _fps[stream_type];};

private:
bool isSameProfileValues(const rs2::stream_profile& profile, const int width, const int height, const int fps, const rs2_format format);
rs2::stream_profile validateAndGetSuitableProfile(rs2_stream stream_type, rs2::stream_profile given_profile);
void registerVideoSensorProfileFormat(stream_index_pair sip);
void registerVideoSensorParams(std::set<stream_index_pair> sips);
std::string get_profiles_descriptions();
std::string get_profiles_descriptions(rs2_stream stream_type);
std::string getProfileFormatsDescriptions(stream_index_pair sip);

private:
std::string _module_name;
std::map<stream_index_pair, rs2_format> _formats;
int _fps;
int _width, _height;
std::map<rs2_stream, int> _fps, _width, _height;
bool _is_profile_exist;
bool _force_image_default_qos;
};
Expand Down
8 changes: 5 additions & 3 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,16 @@
{'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'},
{'name': 'output', 'default': 'screen', 'description': 'pipe node output [screen|log]'},
{'name': 'enable_color', 'default': 'true', 'description': 'enable color stream'},
{'name': 'rgb_camera.profile', 'default': '0,0,0', 'description': 'color image width'},
{'name': 'rgb_camera.color_profile', 'default': '0,0,0', 'description': 'color stream profile'},
{'name': 'rgb_camera.color_format', 'default': 'RGB8', 'description': 'color stream format'},
{'name': 'rgb_camera.enable_auto_exposure', 'default': 'true', 'description': 'enable/disable auto exposure for color image'},
{'name': 'enable_depth', 'default': 'true', 'description': 'enable depth stream'},
{'name': 'enable_infra', 'default': 'false', 'description': 'enable infra0 stream'},
{'name': 'enable_infra1', 'default': 'false', 'description': 'enable infra1 stream'},
{'name': 'enable_infra2', 'default': 'false', 'description': 'enable infra2 stream'},
{'name': 'depth_module.profile', 'default': '0,0,0', 'description': 'depth module profile'},
{'name': 'depth_module.depth_profile', 'default': '0,0,0', 'description': 'depth stream profile'},
{'name': 'depth_module.depth_format', 'default': 'Z16', 'description': 'depth stream format'},
{'name': 'depth_module.infra_profile', 'default': '0,0,0', 'description': 'infra streams (0/1/2) profile'},
{'name': 'depth_module.infra_format', 'default': 'RGB8', 'description': 'infra0 stream format'},
{'name': 'depth_module.infra1_format', 'default': 'Y8', 'description': 'infra1 stream format'},
{'name': 'depth_module.infra2_format', 'default': 'Y8', 'description': 'infra2 stream format'},
Expand Down Expand Up @@ -83,8 +84,9 @@
{'name': 'reconnect_timeout', 'default': '6.', 'description': 'Timeout(seconds) between consequtive reconnection attempts'},
{'name': 'enable_safety', 'default': 'false', 'description': "'enable safety stream'"},
{'name': 'enable_labeled_point_cloud', 'default': 'false', 'description': "'enable labeled point cloud stream'"},
{'name': 'depth_mapping_camera.labeled_point_cloud_profile', 'default': '0,0,0', 'description': "'Label PointCloud stream profile'"},
{'name': 'enable_occupancy', 'default': 'false', 'description': "'enable occupancy stream'"},
{'name': 'depth_mapping_camera.profile', 'default': '0,0,0', 'description': "'depth mapping camera profile'"},
{'name': 'depth_mapping_camera.occupancy_profile', 'default': '0,0,0', 'description': "'Occupancy stream profile'"},
]

def declare_configurable_parameters(parameters):
Expand Down
Loading
Loading