Public Member Functions | Public Attributes | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
ADI3DToFImageStitching Class Reference

This is main class for this package. More...

#include <adi_3dtof_image_stitching.h>

Inheritance diagram for ADI3DToFImageStitching:
Inheritance graph
[legend]

Public Member Functions

template<typename T >
void addInputNodeToQueue (T *image_stitch_input_info)
 
 ADI3DToFImageStitching ()
 Construct a new ADI3DToFImageStitching object. More...
 
void AutoscaleStitching (ADI3DToFImageStitchingInputInfo *image_stitch_input_info)
 Calculates Yaw correction and updates output size. More...
 
void camInfoCallback (const sensor_msgs::CameraInfoConstPtr &cam_info, int cam_id)
 Low-level callback for Com-Info the ID would indicate the source camera. More...
 
sensor_msgs::PointCloud2::Ptr convert2ROSPointCloudMsg (short *xyz_frame, std_msgs::Header sensor_header, int img_width, int img_height)
 COnvery XYZ 3D fram to ROS point cloud message format. More...
 
void depthImageCallback (const sensor_msgs::ImageConstPtr &depth_image, int cam_id, ADI3DToFImageStitchingInputInfo *image_stitch_input_info)
 Low-level callback for depth image. More...
 
void generatePointCloud (float *xyz_frame, int *lut_3d_to_2d_mapping, const pcl::PointCloud< pcl::PointXYZ >::Ptr &out_pointcloud)
 Function to convert 3D XYZ frame to PCL point cloud format. More...
 
ADI3DToFImageStitchingInputInfogetInputNode ()
 Function to read the next node from the input Queue. More...
 
void inputReadAbort ()
 
void irImageCallback (const sensor_msgs::ImageConstPtr &ir_image, int cam_id, ADI3DToFImageStitchingInputInfo *image_stitch_input_info)
 Low-level callback for IR image. More...
 
void processOutput ()
 The output process function, this is running a loop which reads the frame from the putput queue, generates the visualization output and publishes the output as ROS messages. More...
 
void processOutputAbort ()
 This function sets the abort flag for the output thread, the function is normally called by the main function to abort the output thread. More...
 
void pushOutputNode (ADI3DToFImageStitchingOutputInfo *new_output_node)
 This function pushes the debug node to the output queue. If the queue is full, then the last item in the queue gets replaced with the latest node. More...
 
void shutDownAllNodes ()
 This function shuts down all the nodes running in a roscore. More...
 
bool stitchFrames ()
 Stitch function. More...
 
void sync2CamerasCamInfoCallback (const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam1, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam2)
 Call back for synchronised topics(CameraInfo) for 2 camera configuration. More...
 
void sync2CamerasDepthIRImageCallback (const sensor_msgs::ImageConstPtr &depth_image_cam1, const sensor_msgs::ImageConstPtr &ir_image_cam1, const sensor_msgs::ImageConstPtr &depth_image_cam2, const sensor_msgs::ImageConstPtr &ir_image_cam2)
 Call back for synchronised topics(depth and IR image pair) for 2 camera configuration. More...
 
void sync3CamerasCamInfoCallback (const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam1, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam2, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam3)
 Call back for synchronised topics(CameraInfo) for 3 camera configuration. More...
 
void sync3CamerasDepthIRImageCallback (const sensor_msgs::ImageConstPtr &depth_image_cam1, const sensor_msgs::ImageConstPtr &ir_image_cam1, const sensor_msgs::ImageConstPtr &depth_image_cam2, const sensor_msgs::ImageConstPtr &ir_image_cam2, const sensor_msgs::ImageConstPtr &depth_image_cam3, const sensor_msgs::ImageConstPtr &ir_image_cam3)
 Call back for synchronised topics(depth and IR image pair) for 3 camera configuration. More...
 
void sync4CamerasCamInfoCallback (const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam1, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam2, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam3, const sensor_msgs::CameraInfoConstPtr &CameraInfo_cam4)
 Call back for synchronised topics(CameraInfo) for 4 camera configuration. More...
 
void sync4CamerasDepthIRImageCallback (const sensor_msgs::ImageConstPtr &depth_image_cam1, const sensor_msgs::ImageConstPtr &ir_image_cam1, const sensor_msgs::ImageConstPtr &depth_image_cam2, const sensor_msgs::ImageConstPtr &ir_image_cam2, const sensor_msgs::ImageConstPtr &depth_image_cam3, const sensor_msgs::ImageConstPtr &ir_image_cam3, const sensor_msgs::ImageConstPtr &depth_image_cam4, const sensor_msgs::ImageConstPtr &ir_image_cam4)
 Call back for synchronised topics(depth and IR image pair) for 4 camera configuration. More...
 
 ~ADI3DToFImageStitching ()
 Destroy the ADI3DToFImageStitching object. More...
 
- Public Member Functions inherited from ros::NodeHandle
Publisher advertise (AdvertiseOptions &ops)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, bool latch=false)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const VoidConstPtr &tracked_object=VoidConstPtr(), bool latch=false)
 
ServiceServer advertiseService (AdvertiseServiceOptions &ops)
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(MReq &, MRes &))
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
SteadyTimer createSteadyTimer (SteadyTimerOptions &ops) const
 
SteadyTimer createSteadyTimer (WallDuration period, const SteadyTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &) const, T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (TimerOptions &ops) const
 
WallTimer createWallTimer (WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallTimerOptions &ops) const
 
bool deleteParam (const std::string &key) const
 
CallbackQueueInterfacegetCallbackQueue () const
 
const std::string & getNamespace () const
 
bool getParam (const std::string &key, bool &b) const
 
bool getParam (const std::string &key, double &d) const
 
bool getParam (const std::string &key, float &f) const
 
bool getParam (const std::string &key, int &i) const
 
bool getParam (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParam (const std::string &key, std::map< std::string, double > &map) const
 
bool getParam (const std::string &key, std::map< std::string, float > &map) const
 
bool getParam (const std::string &key, std::map< std::string, int > &map) const
 
bool getParam (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParam (const std::string &key, std::string &s) const
 
bool getParam (const std::string &key, std::vector< bool > &vec) const
 
bool getParam (const std::string &key, std::vector< double > &vec) const
 
bool getParam (const std::string &key, std::vector< float > &vec) const
 
bool getParam (const std::string &key, std::vector< int > &vec) const
 
bool getParam (const std::string &key, std::vector< std::string > &vec) const
 
bool getParam (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamCached (const std::string &key, bool &b) const
 
bool getParamCached (const std::string &key, double &d) const
 
bool getParamCached (const std::string &key, float &f) const
 
bool getParamCached (const std::string &key, int &i) const
 
bool getParamCached (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, double > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, float > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, int > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParamCached (const std::string &key, std::string &s) const
 
bool getParamCached (const std::string &key, std::vector< bool > &vec) const
 
bool getParamCached (const std::string &key, std::vector< double > &vec) const
 
bool getParamCached (const std::string &key, std::vector< float > &vec) const
 
bool getParamCached (const std::string &key, std::vector< int > &vec) const
 
bool getParamCached (const std::string &key, std::vector< std::string > &vec) const
 
bool getParamCached (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamNames (std::vector< std::string > &keys) const
 
const std::string & getUnresolvedNamespace () const
 
bool hasParam (const std::string &key) const
 
 NodeHandle (const NodeHandle &parent, const std::string &ns)
 
 NodeHandle (const NodeHandle &parent, const std::string &ns, const M_string &remappings)
 
 NodeHandle (const NodeHandle &rhs)
 
 NodeHandle (const std::string &ns=std::string(), const M_string &remappings=M_string())
 
bool ok () const
 
NodeHandleoperator= (const NodeHandle &rhs)
 
param (const std::string &param_name, const T &default_val) const
 
bool param (const std::string &param_name, T &param_val, const T &default_val) const
 
std::string resolveName (const std::string &name, bool remap=true) const
 
bool searchParam (const std::string &key, std::string &result) const
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (ServiceClientOptions &ops)
 
void setCallbackQueue (CallbackQueueInterface *queue)
 
void setParam (const std::string &key, bool b) const
 
void setParam (const std::string &key, const char *s) const
 
void setParam (const std::string &key, const std::map< std::string, bool > &map) const
 
void setParam (const std::string &key, const std::map< std::string, double > &map) const
 
void setParam (const std::string &key, const std::map< std::string, float > &map) const
 
void setParam (const std::string &key, const std::map< std::string, int > &map) const
 
void setParam (const std::string &key, const std::map< std::string, std::string > &map) const
 
void setParam (const std::string &key, const std::string &s) const
 
void setParam (const std::string &key, const std::vector< bool > &vec) const
 
void setParam (const std::string &key, const std::vector< double > &vec) const
 
void setParam (const std::string &key, const std::vector< float > &vec) const
 
void setParam (const std::string &key, const std::vector< int > &vec) const
 
void setParam (const std::string &key, const std::vector< std::string > &vec) const
 
void setParam (const std::string &key, const XmlRpc::XmlRpcValue &v) const
 
void setParam (const std::string &key, double d) const
 
void setParam (const std::string &key, int i) const
 
void shutdown ()
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (SubscribeOptions &ops)
 
 ~NodeHandle ()
 

Public Attributes

bool camera_parameters_updated_ [MAX_NUM_DEVICES] = { false }
 
float horizontal_fov_sensor_in_degrees_ = 75.0f
 
int out_image_height_ = 512
 
int out_image_width_ = 512 * MAX_NUM_DEVICES
 
float vertical_fov_sensor_in_degrees_ = 75.0f
 

Static Public Attributes

static const int MAX_NUM_DEVICES = 4
 

Private Types

typedef void(ADI3DToFImageStitching::* ImageCallbackFuncPointer) (const sensor_msgs::ImageConstPtr &)
 
typedef void(ADI3DToFImageStitching::* ObjectDetectCallbackFuncPointer) (const std_msgs::BoolConstPtr &)
 
typedef void(ADI3DToFImageStitching::* PointCloudCallbackFuncPointer) (const sensor_msgs::PointCloud2ConstPtr &)
 

Private Member Functions

void fillAndPublishCameraInfo (std::string frame_id, const ros::Publisher &publisher)
 This image fills and publishes the camera information. More...
 
void populateCameraInstrinsics (CameraIntrinsics &camera_intrinsics)
 Populate camera Intrinsic data. More...
 
void publishImageAsRosMsg (cv::Mat img, const std::string &encoding_type, std::string frame_id, const ros::Publisher &publisher)
 This function publishes images as Ros messages. More...
 

Private Attributes

bool autoscaling_flag_
 
sensor_msgs::CameraInfo cam_info_msg_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > camera_info_subscriber_ [MAX_NUM_DEVICES]
 
std::string camera_link_
 
geometry_msgs::TransformStamped camera_map_transform_ [MAX_NUM_DEVICES]
 
float camera_yaw_ [MAX_NUM_DEVICES]
 
float camera_yaw_correction_
 
float camera_yaw_max_
 
float camera_yaw_min_
 
ros::Publisher combo_out_point_cloud_publisher_
 
ros::Time curr_frame_timestamp_ = ros::Time::now()
 
bool depth_image_recvd_ [MAX_NUM_DEVICES]
 
image_transport::SubscriberFilter depth_image_subscriber_ [MAX_NUM_DEVICES]
 
CameraIntrinsics depth_intrinsics_
 
bool enable_autoscaling_
 
int enable_pointcloud_generation_
 
int frame_counter_
 
ImageProcUtilsimage_proc_utils_ [MAX_NUM_DEVICES]
 
std::queue< ADI3DToFImageStitchingInputInfo * > input_node_queue_
 
int input_queue_length_
 
bool input_read_abort_
 
boost::mutex input_thread_mtx_
 
bool ir_image_recvd_ [MAX_NUM_DEVICES]
 
image_transport::SubscriberFilter ir_image_subscriber_ [MAX_NUM_DEVICES]
 
image_transport::ImageTransportit_
 
int num_sensors_
 
std::string output_file_name_
 
std::queue< ADI3DToFImageStitchingOutputInfo * > output_node_queue_
 
int output_queue_length_
 
IOutputSensoroutput_sensor_
 
int output_sensor_mode_
 
boost::mutex output_thread_mtx_
 
bool process_output_thread_abort_ = false
 
int sensor_image_height_
 
int sensor_image_width_
 
StitchFramesCoreCPUstitch_frames_core_CPU_
 
ros::Publisher stitched_camera_info_publisher_
 
ros::Publisher stitched_depth_image_publisher_
 
ros::Publisher stitched_ir_image_publisher_
 
sensor_msgs::PointCloud2 stitched_pc_
 
pcl::PointCloud< pcl::PointXYZ >::Ptr stitched_pc_pcl_
 
boost::shared_ptr< sync_CamInfo_2camsync_CamInfo_2cam_
 
boost::shared_ptr< sync_CamInfo_3camsync_CamInfo_3cam_
 
boost::shared_ptr< sync_CamInfo_4camsync_CamInfo_4cam_
 
boost::shared_ptr< sync_depth_ir_2camsync_depth_ir_2cam_
 
boost::shared_ptr< sync_depth_ir_3camsync_depth_ir_3cam_
 
boost::shared_ptr< sync_depth_ir_4camsync_depth_ir_4cam_
 
tf2_ros::Buffer tf_buffer_ [MAX_NUM_DEVICES]
 
tf2_ros::TransformListenertf_listener_ [MAX_NUM_DEVICES]
 
bool tf_recvd_ [MAX_NUM_DEVICES]
 
float transform_matrix_ [MAX_NUM_DEVICES][16]
 

Detailed Description

This is main class for this package.

Definition at line 97 of file adi_3dtof_image_stitching.h.

Member Typedef Documentation

◆ ImageCallbackFuncPointer

typedef void(ADI3DToFImageStitching::* ADI3DToFImageStitching::ImageCallbackFuncPointer) (const sensor_msgs::ImageConstPtr &)
private

Definition at line 99 of file adi_3dtof_image_stitching.h.

◆ ObjectDetectCallbackFuncPointer

typedef void(ADI3DToFImageStitching::* ADI3DToFImageStitching::ObjectDetectCallbackFuncPointer) (const std_msgs::BoolConstPtr &)
private

Definition at line 100 of file adi_3dtof_image_stitching.h.

◆ PointCloudCallbackFuncPointer

typedef void(ADI3DToFImageStitching::* ADI3DToFImageStitching::PointCloudCallbackFuncPointer) (const sensor_msgs::PointCloud2ConstPtr &)
private

Definition at line 101 of file adi_3dtof_image_stitching.h.

Constructor & Destructor Documentation

◆ ADI3DToFImageStitching()

ADI3DToFImageStitching::ADI3DToFImageStitching ( )
inline

Construct a new ADI3DToFImageStitching object.

Todo:
Add Exception handling codes

Definition at line 115 of file adi_3dtof_image_stitching.h.

◆ ~ADI3DToFImageStitching()

ADI3DToFImageStitching::~ADI3DToFImageStitching ( )
inline

Destroy the ADI3DToFImageStitching object.

Definition at line 304 of file adi_3dtof_image_stitching.h.

Member Function Documentation

◆ addInputNodeToQueue()

template<typename T >
void ADI3DToFImageStitching::addInputNodeToQueue ( T *  image_stitch_input_info)

Definition at line 496 of file callback_impl.cpp.

◆ AutoscaleStitching()

void ADI3DToFImageStitching::AutoscaleStitching ( ADI3DToFImageStitchingInputInfo image_stitch_input_info)

Calculates Yaw correction and updates output size.

Parameters
image_stitch_input_info- input object to calculate yaw correction

Definition at line 24 of file callback_impl.cpp.

◆ camInfoCallback()

void ADI3DToFImageStitching::camInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  cam_info,
int  cam_id 
)

Low-level callback for Com-Info the ID would indicate the source camera.

Parameters
cam_info- Cam Info Pointer
cam_id- Camera Id

Definition at line 319 of file callback_impl.cpp.

◆ convert2ROSPointCloudMsg()

sensor_msgs::PointCloud2::Ptr ADI3DToFImageStitching::convert2ROSPointCloudMsg ( short *  xyz_frame,
std_msgs::Header  sensor_header,
int  img_width,
int  img_height 
)
inline

COnvery XYZ 3D fram to ROS point cloud message format.

Parameters
xyz_frame- input xyz frame
sensor_header- sensor header data
img_width- xyz frame width
img_height- xyz frame height
Returns
sensor_msgs::PointCloud2::Ptr

Definition at line 327 of file adi_3dtof_image_stitching.h.

◆ depthImageCallback()

void ADI3DToFImageStitching::depthImageCallback ( const sensor_msgs::ImageConstPtr &  depth_image,
int  cam_id,
ADI3DToFImageStitchingInputInfo image_stitch_input_info 
)

Low-level callback for depth image.

Parameters
depth_image- Pointer to depth image
cam_id- Camera ID
image_stitch_input_info- input object to load recieved depth data Note: depth image is assumed to be 16 bpp image.

Definition at line 369 of file callback_impl.cpp.

◆ fillAndPublishCameraInfo()

void ADI3DToFImageStitching::fillAndPublishCameraInfo ( std::string  frame_id,
const ros::Publisher publisher 
)
inlineprivate

This image fills and publishes the camera information.

Parameters
frame_idframe_id of camera_info
publisherThis is Ros publisher

Definition at line 523 of file adi_3dtof_image_stitching.h.

◆ generatePointCloud()

void ADI3DToFImageStitching::generatePointCloud ( float *  xyz_frame,
int *  lut_3d_to_2d_mapping,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  out_pointcloud 
)

Function to convert 3D XYZ frame to PCL point cloud format.

Parameters
xyz_frame- Input XYZ frame
out_pointcloud- PCl point cloud output

Definition at line 108 of file stitch_frames.cpp.

◆ getInputNode()

ADI3DToFImageStitchingInputInfo * ADI3DToFImageStitching::getInputNode ( )

Function to read the next node from the input Queue.

Returns
ADI3DToFImageStitchingInputInfo* - Pointer to the next node

Definition at line 136 of file stitch_frames.cpp.

◆ inputReadAbort()

void ADI3DToFImageStitching::inputReadAbort ( )
inline

Definition at line 417 of file adi_3dtof_image_stitching.h.

◆ irImageCallback()

void ADI3DToFImageStitching::irImageCallback ( const sensor_msgs::ImageConstPtr &  ir_image,
int  cam_id,
ADI3DToFImageStitchingInputInfo image_stitch_input_info 
)

Low-level callback for IR image.

Parameters
ir_image- IR image message pointer
cam_id- Camera ID
image_stitch_input_info- input object to load recieved IR data Note : IR image is 16bpp image

Definition at line 464 of file callback_impl.cpp.

◆ populateCameraInstrinsics()

void ADI3DToFImageStitching::populateCameraInstrinsics ( CameraIntrinsics camera_intrinsics)
inlineprivate

Populate camera Intrinsic data.

Parameters
camera_intrinsics- input camera intrinsic

Definition at line 560 of file adi_3dtof_image_stitching.h.

◆ processOutput()

void ADI3DToFImageStitching::processOutput ( )

The output process function, this is running a loop which reads the frame from the putput queue, generates the visualization output and publishes the output as ROS messages.

Definition at line 65 of file adi_3dtof_image_stitching_output_thread.cpp.

◆ processOutputAbort()

void ADI3DToFImageStitching::processOutputAbort ( )

This function sets the abort flag for the output thread, the function is normally called by the main function to abort the output thread.

Definition at line 18 of file adi_3dtof_image_stitching_output_thread.cpp.

◆ publishImageAsRosMsg()

void ADI3DToFImageStitching::publishImageAsRosMsg ( cv::Mat  img,
const std::string &  encoding_type,
std::string  frame_id,
const ros::Publisher publisher 
)
inlineprivate

This function publishes images as Ros messages.

Parameters
imgThis is input image
encoding_typenumber of bits used to represent one pixel of image.
frame_idframe id of image
publisherThis is ros publisher

Definition at line 503 of file adi_3dtof_image_stitching.h.

◆ pushOutputNode()

void ADI3DToFImageStitching::pushOutputNode ( ADI3DToFImageStitchingOutputInfo new_output_node)

This function pushes the debug node to the output queue. If the queue is full, then the last item in the queue gets replaced with the latest node.

Parameters
new_output_node: Pointer to the debug node o be published

Definition at line 30 of file adi_3dtof_image_stitching_output_thread.cpp.

◆ shutDownAllNodes()

void ADI3DToFImageStitching::shutDownAllNodes ( )
inline

This function shuts down all the nodes running in a roscore.

Definition at line 290 of file adi_3dtof_image_stitching.h.

◆ stitchFrames()

bool ADI3DToFImageStitching::stitchFrames ( )

Stitch function.

Returns
true
false

Definition at line 30 of file stitch_frames.cpp.

◆ sync2CamerasCamInfoCallback()

void ADI3DToFImageStitching::sync2CamerasCamInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam1,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam2 
)

Call back for synchronised topics(CameraInfo) for 2 camera configuration.

Parameters
CameraInfo_cam1- Cam1 CameraInfo pointer
CameraInfo_cam2- Cam2 CameraInfo pointer

Definition at line 266 of file callback_impl.cpp.

◆ sync2CamerasDepthIRImageCallback()

void ADI3DToFImageStitching::sync2CamerasDepthIRImageCallback ( const sensor_msgs::ImageConstPtr &  depth_image_cam1,
const sensor_msgs::ImageConstPtr &  ir_image_cam1,
const sensor_msgs::ImageConstPtr &  depth_image_cam2,
const sensor_msgs::ImageConstPtr &  ir_image_cam2 
)

Call back for synchronised topics(depth and IR image pair) for 2 camera configuration.

Parameters
depth_image_cam1- Cam1 depth image pointer
ir_image_cam1- Cam1 IR image pointer
depth_image_cam2- Cam2 depth image pointer
ir_image_cam2- Cam2 IR image pointer

Definition at line 64 of file callback_impl.cpp.

◆ sync3CamerasCamInfoCallback()

void ADI3DToFImageStitching::sync3CamerasCamInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam1,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam2,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam3 
)

Call back for synchronised topics(CameraInfo) for 3 camera configuration.

Parameters
CameraInfo_cam1- Cam1 CameraInfo pointer
CameraInfo_cam2- Cam2 CameraInfo pointer
CameraInfo_cam3- Cam3 CameraInfo pointer

Definition at line 281 of file callback_impl.cpp.

◆ sync3CamerasDepthIRImageCallback()

void ADI3DToFImageStitching::sync3CamerasDepthIRImageCallback ( const sensor_msgs::ImageConstPtr &  depth_image_cam1,
const sensor_msgs::ImageConstPtr &  ir_image_cam1,
const sensor_msgs::ImageConstPtr &  depth_image_cam2,
const sensor_msgs::ImageConstPtr &  ir_image_cam2,
const sensor_msgs::ImageConstPtr &  depth_image_cam3,
const sensor_msgs::ImageConstPtr &  ir_image_cam3 
)

Call back for synchronised topics(depth and IR image pair) for 3 camera configuration.

Parameters
depth_image_cam1- Cam1 depth image pointer
ir_image_cam1- Cam1 IR image pointer
depth_image_cam2- Cam2 depth image pointer
ir_image_cam2- Cam2 IR image pointer
depth_image_cam3- Cam3 depth image pointer
ir_image_cam3- Cam3 IR image pointer

Definition at line 110 of file callback_impl.cpp.

◆ sync4CamerasCamInfoCallback()

void ADI3DToFImageStitching::sync4CamerasCamInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam1,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam2,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam3,
const sensor_msgs::CameraInfoConstPtr &  CameraInfo_cam4 
)

Call back for synchronised topics(CameraInfo) for 4 camera configuration.

Parameters
CameraInfo_cam1- Cam1 CameraInfo pointer
CameraInfo_cam2- Cam2 CameraInfo pointer
CameraInfo_cam3- Cam3 CameraInfo pointer
CameraInfo_cam4- Cam4 CameraInfo pointer

Definition at line 300 of file callback_impl.cpp.

◆ sync4CamerasDepthIRImageCallback()

void ADI3DToFImageStitching::sync4CamerasDepthIRImageCallback ( const sensor_msgs::ImageConstPtr &  depth_image_cam1,
const sensor_msgs::ImageConstPtr &  ir_image_cam1,
const sensor_msgs::ImageConstPtr &  depth_image_cam2,
const sensor_msgs::ImageConstPtr &  ir_image_cam2,
const sensor_msgs::ImageConstPtr &  depth_image_cam3,
const sensor_msgs::ImageConstPtr &  ir_image_cam3,
const sensor_msgs::ImageConstPtr &  depth_image_cam4,
const sensor_msgs::ImageConstPtr &  ir_image_cam4 
)

Call back for synchronised topics(depth and IR image pair) for 4 camera configuration.

Parameters
depth_image_cam1- Cam1 depth image pointer
ir_image_cam1- Cam1 IR image pointer
depth_image_cam2- Cam2 depth image pointer
ir_image_cam2- Cam2 IR image pointer
depth_image_cam3- Cam3 depth image pointer
ir_image_cam3- Cam3 IR image pointer
depth_image_cam4- Cam4 depth image pointer
ir_image_cam4- Cam4 IR image pointer

Definition at line 187 of file callback_impl.cpp.

Member Data Documentation

◆ autoscaling_flag_

bool ADI3DToFImageStitching::autoscaling_flag_
private

Definition at line 440 of file adi_3dtof_image_stitching.h.

◆ cam_info_msg_

sensor_msgs::CameraInfo ADI3DToFImageStitching::cam_info_msg_
private

Definition at line 433 of file adi_3dtof_image_stitching.h.

◆ camera_info_subscriber_

message_filters::Subscriber<sensor_msgs::CameraInfo> ADI3DToFImageStitching::camera_info_subscriber_[MAX_NUM_DEVICES]
private

Definition at line 443 of file adi_3dtof_image_stitching.h.

◆ camera_link_

std::string ADI3DToFImageStitching::camera_link_
private

Definition at line 432 of file adi_3dtof_image_stitching.h.

◆ camera_map_transform_

geometry_msgs::TransformStamped ADI3DToFImageStitching::camera_map_transform_[MAX_NUM_DEVICES]
private

Definition at line 453 of file adi_3dtof_image_stitching.h.

◆ camera_parameters_updated_

bool ADI3DToFImageStitching::camera_parameters_updated_[MAX_NUM_DEVICES] = { false }

Definition at line 105 of file adi_3dtof_image_stitching.h.

◆ camera_yaw_

float ADI3DToFImageStitching::camera_yaw_[MAX_NUM_DEVICES]
private

Definition at line 452 of file adi_3dtof_image_stitching.h.

◆ camera_yaw_correction_

float ADI3DToFImageStitching::camera_yaw_correction_
private

Definition at line 456 of file adi_3dtof_image_stitching.h.

◆ camera_yaw_max_

float ADI3DToFImageStitching::camera_yaw_max_
private

Definition at line 455 of file adi_3dtof_image_stitching.h.

◆ camera_yaw_min_

float ADI3DToFImageStitching::camera_yaw_min_
private

Definition at line 454 of file adi_3dtof_image_stitching.h.

◆ combo_out_point_cloud_publisher_

ros::Publisher ADI3DToFImageStitching::combo_out_point_cloud_publisher_
private

Definition at line 468 of file adi_3dtof_image_stitching.h.

◆ curr_frame_timestamp_

ros::Time ADI3DToFImageStitching::curr_frame_timestamp_ = ros::Time::now()
private

Definition at line 474 of file adi_3dtof_image_stitching.h.

◆ depth_image_recvd_

bool ADI3DToFImageStitching::depth_image_recvd_[MAX_NUM_DEVICES]
private

Definition at line 449 of file adi_3dtof_image_stitching.h.

◆ depth_image_subscriber_

image_transport::SubscriberFilter ADI3DToFImageStitching::depth_image_subscriber_[MAX_NUM_DEVICES]
private

Definition at line 444 of file adi_3dtof_image_stitching.h.

◆ depth_intrinsics_

CameraIntrinsics ADI3DToFImageStitching::depth_intrinsics_
private

Definition at line 434 of file adi_3dtof_image_stitching.h.

◆ enable_autoscaling_

bool ADI3DToFImageStitching::enable_autoscaling_
private

Definition at line 439 of file adi_3dtof_image_stitching.h.

◆ enable_pointcloud_generation_

int ADI3DToFImageStitching::enable_pointcloud_generation_
private

Definition at line 436 of file adi_3dtof_image_stitching.h.

◆ frame_counter_

int ADI3DToFImageStitching::frame_counter_
private

Definition at line 431 of file adi_3dtof_image_stitching.h.

◆ horizontal_fov_sensor_in_degrees_

float ADI3DToFImageStitching::horizontal_fov_sensor_in_degrees_ = 75.0f

Definition at line 107 of file adi_3dtof_image_stitching.h.

◆ image_proc_utils_

ImageProcUtils* ADI3DToFImageStitching::image_proc_utils_[MAX_NUM_DEVICES]
private

Definition at line 435 of file adi_3dtof_image_stitching.h.

◆ input_node_queue_

std::queue<ADI3DToFImageStitchingInputInfo*> ADI3DToFImageStitching::input_node_queue_
private

Definition at line 488 of file adi_3dtof_image_stitching.h.

◆ input_queue_length_

int ADI3DToFImageStitching::input_queue_length_
private

Definition at line 478 of file adi_3dtof_image_stitching.h.

◆ input_read_abort_

bool ADI3DToFImageStitching::input_read_abort_
private

Definition at line 486 of file adi_3dtof_image_stitching.h.

◆ input_thread_mtx_

boost::mutex ADI3DToFImageStitching::input_thread_mtx_
private

Definition at line 484 of file adi_3dtof_image_stitching.h.

◆ ir_image_recvd_

bool ADI3DToFImageStitching::ir_image_recvd_[MAX_NUM_DEVICES]
private

Definition at line 448 of file adi_3dtof_image_stitching.h.

◆ ir_image_subscriber_

image_transport::SubscriberFilter ADI3DToFImageStitching::ir_image_subscriber_[MAX_NUM_DEVICES]
private

Definition at line 445 of file adi_3dtof_image_stitching.h.

◆ it_

image_transport::ImageTransport* ADI3DToFImageStitching::it_
private

Definition at line 442 of file adi_3dtof_image_stitching.h.

◆ MAX_NUM_DEVICES

const int ADI3DToFImageStitching::MAX_NUM_DEVICES = 4
static

Definition at line 104 of file adi_3dtof_image_stitching.h.

◆ num_sensors_

int ADI3DToFImageStitching::num_sensors_
private

Definition at line 476 of file adi_3dtof_image_stitching.h.

◆ out_image_height_

int ADI3DToFImageStitching::out_image_height_ = 512

Definition at line 108 of file adi_3dtof_image_stitching.h.

◆ out_image_width_

int ADI3DToFImageStitching::out_image_width_ = 512 * MAX_NUM_DEVICES

Definition at line 109 of file adi_3dtof_image_stitching.h.

◆ output_file_name_

std::string ADI3DToFImageStitching::output_file_name_
private

Definition at line 438 of file adi_3dtof_image_stitching.h.

◆ output_node_queue_

std::queue<ADI3DToFImageStitchingOutputInfo*> ADI3DToFImageStitching::output_node_queue_
private

Definition at line 489 of file adi_3dtof_image_stitching.h.

◆ output_queue_length_

int ADI3DToFImageStitching::output_queue_length_
private

Definition at line 479 of file adi_3dtof_image_stitching.h.

◆ output_sensor_

IOutputSensor* ADI3DToFImageStitching::output_sensor_
private

Definition at line 428 of file adi_3dtof_image_stitching.h.

◆ output_sensor_mode_

int ADI3DToFImageStitching::output_sensor_mode_
private

Definition at line 437 of file adi_3dtof_image_stitching.h.

◆ output_thread_mtx_

boost::mutex ADI3DToFImageStitching::output_thread_mtx_
private

Definition at line 483 of file adi_3dtof_image_stitching.h.

◆ process_output_thread_abort_

bool ADI3DToFImageStitching::process_output_thread_abort_ = false
private

Definition at line 481 of file adi_3dtof_image_stitching.h.

◆ sensor_image_height_

int ADI3DToFImageStitching::sensor_image_height_
private

Definition at line 430 of file adi_3dtof_image_stitching.h.

◆ sensor_image_width_

int ADI3DToFImageStitching::sensor_image_width_
private

Definition at line 429 of file adi_3dtof_image_stitching.h.

◆ stitch_frames_core_CPU_

StitchFramesCoreCPU* ADI3DToFImageStitching::stitch_frames_core_CPU_
private

Definition at line 493 of file adi_3dtof_image_stitching.h.

◆ stitched_camera_info_publisher_

ros::Publisher ADI3DToFImageStitching::stitched_camera_info_publisher_
private

Definition at line 469 of file adi_3dtof_image_stitching.h.

◆ stitched_depth_image_publisher_

ros::Publisher ADI3DToFImageStitching::stitched_depth_image_publisher_
private

Definition at line 466 of file adi_3dtof_image_stitching.h.

◆ stitched_ir_image_publisher_

ros::Publisher ADI3DToFImageStitching::stitched_ir_image_publisher_
private

Definition at line 467 of file adi_3dtof_image_stitching.h.

◆ stitched_pc_

sensor_msgs::PointCloud2 ADI3DToFImageStitching::stitched_pc_
private

Definition at line 471 of file adi_3dtof_image_stitching.h.

◆ stitched_pc_pcl_

pcl::PointCloud<pcl::PointXYZ>::Ptr ADI3DToFImageStitching::stitched_pc_pcl_
private

Definition at line 472 of file adi_3dtof_image_stitching.h.

◆ sync_CamInfo_2cam_

boost::shared_ptr<sync_CamInfo_2cam> ADI3DToFImageStitching::sync_CamInfo_2cam_
private

Definition at line 459 of file adi_3dtof_image_stitching.h.

◆ sync_CamInfo_3cam_

boost::shared_ptr<sync_CamInfo_3cam> ADI3DToFImageStitching::sync_CamInfo_3cam_
private

Definition at line 460 of file adi_3dtof_image_stitching.h.

◆ sync_CamInfo_4cam_

boost::shared_ptr<sync_CamInfo_4cam> ADI3DToFImageStitching::sync_CamInfo_4cam_
private

Definition at line 461 of file adi_3dtof_image_stitching.h.

◆ sync_depth_ir_2cam_

boost::shared_ptr<sync_depth_ir_2cam> ADI3DToFImageStitching::sync_depth_ir_2cam_
private

Definition at line 462 of file adi_3dtof_image_stitching.h.

◆ sync_depth_ir_3cam_

boost::shared_ptr<sync_depth_ir_3cam> ADI3DToFImageStitching::sync_depth_ir_3cam_
private

Definition at line 463 of file adi_3dtof_image_stitching.h.

◆ sync_depth_ir_4cam_

boost::shared_ptr<sync_depth_ir_4cam> ADI3DToFImageStitching::sync_depth_ir_4cam_
private

Definition at line 464 of file adi_3dtof_image_stitching.h.

◆ tf_buffer_

tf2_ros::Buffer ADI3DToFImageStitching::tf_buffer_[MAX_NUM_DEVICES]
private

Definition at line 446 of file adi_3dtof_image_stitching.h.

◆ tf_listener_

tf2_ros::TransformListener* ADI3DToFImageStitching::tf_listener_[MAX_NUM_DEVICES]
private

Definition at line 447 of file adi_3dtof_image_stitching.h.

◆ tf_recvd_

bool ADI3DToFImageStitching::tf_recvd_[MAX_NUM_DEVICES]
private

Definition at line 450 of file adi_3dtof_image_stitching.h.

◆ transform_matrix_

float ADI3DToFImageStitching::transform_matrix_[MAX_NUM_DEVICES][16]
private

Definition at line 451 of file adi_3dtof_image_stitching.h.

◆ vertical_fov_sensor_in_degrees_

float ADI3DToFImageStitching::vertical_fov_sensor_in_degrees_ = 75.0f

Definition at line 106 of file adi_3dtof_image_stitching.h.


The documentation for this class was generated from the following files:


adi_3dtof_image_stitching
Author(s):
autogenerated on Fri Mar 21 2025 02:27:20