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

The namespace used is: /niryo_robot_vision/

Parameters - Vision

Vision Package’s Parameters
Name Description
frame_rate Stream frame rate
simulation_mode
Set to true if you are using the gazebo simulation.
It will adapt how the node get its video stream
debug_compression_quality Debug Stream compression quality
stream_compression_quality Stream compression quality
subsampling Stream subsampling factor

Publisher - Vision

Vision Package’s Publishers
Name Message Type Description
compressed_video_stream sensor_msgs/CompressedImage Publish the last image read as a compressed image

Services - Vision

Programs manager Services
Name Message Type Description
debug_colors DebugColorDetection Return an annotated image to emphasize what happened with color detection
debug_markers DebugMarkers Return an annotated image to emphasize what happened with markers detection
obj_detection_rel ObjDetection Object detection service
start_stop_video_streaming SetBool Start or Stop video streaming
take_picture TakePicture Save a picture in the specified folder

All these services are available as soon as the node is started.

Dependencies - Vision

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