Class PipelineGenerator

Class Documentation

class PipelineGenerator

Public Functions

~PipelineGenerator() = default
std::string validatePipeline(rclcpp::Node *node, const std::string &typeStr, int sensorNum)

Validates the pipeline type. If the pipeline type is not valid for the number of sensors, it will be changed to the default type.

Parameters:
  • node – The node used for logging

  • type[in] The type

  • sensorNum[in] The sensor number

Returns:

The validated pipeline type.

std::vector<std::unique_ptr<dai_nodes::BaseNode>> createPipeline(rclcpp::Node *node, std::shared_ptr<dai::Device> device, std::shared_ptr<dai::Pipeline> pipeline, const std::string &pipelineType, const std::string &nnType, bool enableImu)

Creates the pipeline by using a plugin. Plugin types need to be of type depthai_ros_driver::pipeline_gen::BasePipeline.

Parameters:
  • node – The node

  • device – The device

  • pipeline – The pipeline

  • pipelineType[in] The pipeline type name (plugin name or one of the default types)

  • nnType[in] The neural network type (none, rgb, spatial)

  • enableImu[in] Indicates if IMU is enabled

Returns:

Vector BaseNodes created.

Protected Attributes

std::unordered_map<std::string, std::string> pluginTypeMap = {{"RGB", "depthai_ros_driver::pipeline_gen::RGB"}, {"RGBD", "depthai_ros_driver::pipeline_gen::RGBD"}, {"RGBSTEREO", "depthai_ros_driver::pipeline_gen::RGBStereo"}, {"STEREO", "depthai_ros_driver::pipeline_gen::Stereo"}, {"DEPTH", "depthai_ros_driver::pipeline_gen::Depth"}, {"CAMARRAY", "depthai_ros_driver::pipeline_gen::CamArray"}}
std::unordered_map<std::string, PipelineType> pipelineTypeMap{{"RGB", PipelineType::RGB}, {"RGBD", PipelineType::RGBD}, {"RGBSTEREO", PipelineType::RGBStereo}, {"STEREO", PipelineType::Stereo}, {"DEPTH", PipelineType::Depth}, {"CAMARRAY", PipelineType::CamArray}}