Niryo_robot_vision¶
This package is the one dealing with all vision related stuff.
Vision Node¶
The ROS Node is made of several services to deal with video streaming, object detection… The node is working exactly the same way if you chose to use it on simulation or reality.
This node can be launched locally in a standalone mode via the command:
roslaunch niryo_robot_vision vision_node_local.launch
Configuration (Frame Per Second, Camera Port, Video Resolution) can be edited in the config file:
- For “standard” Node: niryo_robot_vision/config/video_server_setup.yaml
- For local Node: niryo_robot_vision/config/video_server_setup_local.yaml
It belongs to the ROS namespace: /niryo_robot_vision/
.
Parameters - Vision¶
Name | Description |
---|---|
frame_rate |
Streams frame rate |
simulation_mode |
Sets to true if you are using the gazebo simulation.
It will adapt how the node get its video stream
|
debug_compression_quality |
Debugs Stream compression quality |
stream_compression_quality |
Streams compression quality |
subsampling |
Streams subsampling factor |
Publisher - Vision¶
Name | Message Type | Description |
---|---|---|
compressed_video_stream |
sensor_msgs/CompressedImage | Publishes the last image read as a compressed image |
video_stream_parameters |
ImageParameters | Publishes the brightness, contrast and saturation settings of the video stream |
Services - Vision¶
Name | Message Type | Description |
---|---|---|
debug_colors |
DebugColorDetection | Returns an annotated image to emphasize what happened with color detection |
debug_markers |
DebugMarkers | Returns an annotated image to emphasize what happened with markers detection |
obj_detection_rel |
ObjDetection | Object detection service |
start_stop_video_streaming |
SetBool | Starts or stops video streaming |
take_picture |
TakePicture | Saves a picture in the specified folder |
set_brightness |
SetImageParameter | Sets the brightness of the video stream |
set_contrast |
SetImageParameter | Sets the contrast of the video stream |
set_saturation |
SetImageParameter | Sets the saturation of the video stream |
visualization |
Visualization | Add visuals markers of objects detected by the vision kit to rviz |
All these services are available as soon as the node is started.
Dependencies - Vision¶
Topics files - Vision¶
ImageParameters (Topic)¶
float64 brightness_factor
float64 contrast_factor
float64 saturation_factor
Services files - Vision¶
DebugColorDetection (Service)¶
string color
---
sensor_msgs/CompressedImage img
DebugMarkers (Service)¶
---
bool markers_detected
sensor_msgs/CompressedImage img
ObjDetection (Service)¶
string obj_type
string obj_color
float32 workspace_ratio
bool ret_image
---
int32 status
niryo_robot_msgs/ObjectPose obj_pose
string obj_type
string obj_color
sensor_msgs/CompressedImage img
TakePicture (Service)¶
string path
---
bool success
SetImageParameter (Service)¶
float64 factor
---
int32 status
string message
Visualization (Service)¶
string workspace
bool clearing
---
int32 status