Public Member Functions | Private Member Functions | Private Attributes | List of all members
ADI3DToFADTF31xx Class Reference

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

#include <adi_3dtof_adtf31xx.h>

Inheritance diagram for ADI3DToFADTF31xx:
Inheritance graph
[legend]

Public Member Functions

 ADI3DToFADTF31xx ()
 Construct a new ADI3DToFADTF31xx object. More...
 
ADI3DToFADTF31xxFrameInfoadtf31xxSensorGetNextFrame ()
 Function to read the next frame from the input Queue. More...
 
void adtf31xxSensorPushOutputNode (ADI3DToFADTF31xxOutputInfo *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 dynamicallyReconfigureVariables (adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig &config, uint32_t level)
 new values from dynamic reconfigure are copied to a structure variable here, actual update to individual parameters happens in updateDynamicReconfigureVariablesInputThread function. 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 readInput ()
 This function reads the frmae from the sensor. This runs in a loop, reading the frames and adding them to the input Queue, if the queue is fulll, then the recent buffer is overwritten with the newly read frame. More...
 
void readInputAbort ()
 Function to read Abort flag, this function will be called by the main function to exit the thread. More...
 
bool readNextFrame ()
 This function is the entry point to the sensor node. More...
 
void shutDownAllNodes ()
 This function shuts down all the nodes running in a roscore. More...
 
void updateDynamicReconfigureVariablesInputThread ()
 updates the parameter of input image based on dynamic reconfigure. More...
 
 ~ADI3DToFADTF31xx ()
 Destroy the ADI3DToFADTF31xx 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 ()
 

Private Member Functions

void fillAndPublishCameraInfo (std::string frame_id, const ros::Publisher &publisher)
 This image fills and publishes the camera information. More...
 
void initSettingsForDynamicReconfigure ()
 Dynamic reconfigure initialization. More...
 
void publishImageAndCameraInfo (ADI3DToFADTF31xxOutputInfo *out_frame)
 Publishes the image and camera information. This function publishes the camera information and depth, AB, and confidence images. 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...
 
void publishPointCloud (short *xyz_frame)
 This function publishes the point cloud. More...
 
void publishRVLCompressedImageAsRosMsg (unsigned char *compressed_img, int compressed_img_size, const std::string &encoding_type, std::string frame_id, const ros::Publisher &publisher)
 This function publishes a compressed image as Ros message. More...
 

Private Attributes

unsigned short * ab_frame_
 
ros::Publisher ab_image_publisher_
 
int ab_threshold_ = 10
 
sensor_msgs::CameraInfo cam_info_msg_
 
std::string camera_link_
 
unsigned short * conf_frame_
 
ros::Publisher conf_image_publisher_
 
int confidence_threshold_ = 10
 
ros::Time curr_frame_timestamp_ = ros::Time::now()
 
CameraExtrinsics depth_extrinsics_
 
CameraExtrinsics depth_extrinsics_external_
 
unsigned short * depth_frame_
 
ros::Publisher depth_image_publisher_
 
ros::Publisher depth_info_publisher_
 
CameraIntrinsics depth_intrinsics_
 
dynamic_reconfigure::Server< adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig >::CallbackType dynamic_reconfigure_callbacktype_
 
adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig dynamic_reconfigure_config_
 
bool enable_depth_ab_compression_
 
bool enable_point_cloud_publish_ = false
 
std::string encoding_type_
 
bool error_in_frame_read_ = false
 
int frame_number_
 
int image_height_ = 1024
 
ImageProcUtilsimage_proc_utils_
 
int image_width_ = 1024
 
std::string input_file_name_
 
std::queue< ADI3DToFADTF31xxFrameInfo * > input_frames_queue_
 
IInputSensorinput_sensor_
 
std::string input_sensor_ip_
 
int input_sensor_mode_
 
boost::mutex input_thread_mtx_
 
int jblf_filter_size_ = 7
 
bool jblf_filter_state_ = true
 
int max_debug_queue_length_ = 10
 
int max_input_queue_length_ = 10
 
std::queue< ADI3DToFADTF31xxOutputInfo * > output_node_queue_
 
boost::mutex output_thread_mtx_
 
bool process_output_thread_abort_ = false
 
int processing_scale_ = 2
 This is the scale factor to scale the input image. The processing will happen on the scaled down image The topics and the output coordinates will correspond to the scaled image size. More...
 
int radial_filter_max_threshold_ = 10000
 
int radial_filter_min_threshold_ = 100
 
bool read_input_thread_abort_ = false
 
dynamic_reconfigure::Server< adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig > server_
 
short * xyz_frame_
 
ros::Publisher xyz_image_publisher_
 

Detailed Description

This is main class for this package.

Definition at line 33 of file adi_3dtof_adtf31xx.h.

Constructor & Destructor Documentation

◆ ADI3DToFADTF31xx()

ADI3DToFADTF31xx::ADI3DToFADTF31xx ( )
inline

Construct a new ADI3DToFADTF31xx object.

Parameters
camera_link
virtual_camera_link
safety_zone_radius_mtr
input_sensor_mode

Definition at line 48 of file adi_3dtof_adtf31xx.h.

◆ ~ADI3DToFADTF31xx()

ADI3DToFADTF31xx::~ADI3DToFADTF31xx ( )
inline

Destroy the ADI3DToFADTF31xx object.

Definition at line 219 of file adi_3dtof_adtf31xx.h.

Member Function Documentation

◆ adtf31xxSensorGetNextFrame()

ADI3DToFADTF31xxFrameInfo * ADI3DToFADTF31xx::adtf31xxSensorGetNextFrame ( )

Function to read the next frame from the input Queue.

Returns
ADI3DToFADTF31xxFrameInfo* - Pointer to the next frame

Definition at line 27 of file adi_3dtof_adtf31xx_input_thread.cpp.

◆ adtf31xxSensorPushOutputNode()

void ADI3DToFADTF31xx::adtf31xxSensorPushOutputNode ( ADI3DToFADTF31xxOutputInfo 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 34 of file adi_3dtof_adtf31xx_output_thread.cpp.

◆ dynamicallyReconfigureVariables()

void ADI3DToFADTF31xx::dynamicallyReconfigureVariables ( adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig &  config,
uint32_t  level 
)

new values from dynamic reconfigure are copied to a structure variable here, actual update to individual parameters happens in updateDynamicReconfigureVariablesInputThread function.

Parameters
configConfig parameters present in GUI
level

Definition at line 164 of file adi_3dtof_adtf31xx.cpp.

◆ fillAndPublishCameraInfo()

void ADI3DToFADTF31xx::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 307 of file adi_3dtof_adtf31xx.h.

◆ initSettingsForDynamicReconfigure()

void ADI3DToFADTF31xx::initSettingsForDynamicReconfigure ( )
private

Dynamic reconfigure initialization.

Definition at line 180 of file adi_3dtof_adtf31xx.cpp.

◆ processOutput()

void ADI3DToFADTF31xx::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 69 of file adi_3dtof_adtf31xx_output_thread.cpp.

◆ processOutputAbort()

void ADI3DToFADTF31xx::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 22 of file adi_3dtof_adtf31xx_output_thread.cpp.

◆ publishImageAndCameraInfo()

void ADI3DToFADTF31xx::publishImageAndCameraInfo ( ADI3DToFADTF31xxOutputInfo out_frame)
inlineprivate

Publishes the image and camera information. This function publishes the camera information and depth, AB, and confidence images.

Parameters
out_framePointer to the output frame containing the compressed depth frame and its size.

Definition at line 433 of file adi_3dtof_adtf31xx.h.

◆ publishImageAsRosMsg()

void ADI3DToFADTF31xx::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 366 of file adi_3dtof_adtf31xx.h.

◆ publishPointCloud()

void ADI3DToFADTF31xx::publishPointCloud ( short *  xyz_frame)
inlineprivate

This function publishes the point cloud.

Parameters
xyz_frame- Pointer to xyz frame

Note: Assumes that cam_info_msg_ is already populated

Definition at line 387 of file adi_3dtof_adtf31xx.h.

◆ publishRVLCompressedImageAsRosMsg()

void ADI3DToFADTF31xx::publishRVLCompressedImageAsRosMsg ( unsigned char *  compressed_img,
int  compressed_img_size,
const std::string &  encoding_type,
std::string  frame_id,
const ros::Publisher publisher 
)
inlineprivate

This function publishes a compressed image as Ros message.

Parameters
compressed_imgCompressed image buffer
compressed_img_sizeCompressed image size in bytes
encoding_typenumber of bits used to represent one pixel of image.
frame_idframe id of image
publisherROS publisher handle

Definition at line 485 of file adi_3dtof_adtf31xx.h.

◆ readInput()

void ADI3DToFADTF31xx::readInput ( )

This function reads the frmae from the sensor. This runs in a loop, reading the frames and adding them to the input Queue, if the queue is fulll, then the recent buffer is overwritten with the newly read frame.

Definition at line 63 of file adi_3dtof_adtf31xx_input_thread.cpp.

◆ readInputAbort()

void ADI3DToFADTF31xx::readInputAbort ( )

Function to read Abort flag, this function will be called by the main function to exit the thread.

Definition at line 17 of file adi_3dtof_adtf31xx_input_thread.cpp.

◆ readNextFrame()

bool ADI3DToFADTF31xx::readNextFrame ( )

This function is the entry point to the sensor node.

Definition at line 86 of file adi_3dtof_adtf31xx.cpp.

◆ shutDownAllNodes()

void ADI3DToFADTF31xx::shutDownAllNodes ( )
inline

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

Definition at line 205 of file adi_3dtof_adtf31xx.h.

◆ updateDynamicReconfigureVariablesInputThread()

void ADI3DToFADTF31xx::updateDynamicReconfigureVariablesInputThread ( )

updates the parameter of input image based on dynamic reconfigure.

Definition at line 34 of file adi_3dtof_adtf31xx.cpp.

Member Data Documentation

◆ ab_frame_

unsigned short* ADI3DToFADTF31xx::ab_frame_
private

Definition at line 258 of file adi_3dtof_adtf31xx.h.

◆ ab_image_publisher_

ros::Publisher ADI3DToFADTF31xx::ab_image_publisher_
private

Definition at line 262 of file adi_3dtof_adtf31xx.h.

◆ ab_threshold_

int ADI3DToFADTF31xx::ab_threshold_ = 10
private

Definition at line 246 of file adi_3dtof_adtf31xx.h.

◆ cam_info_msg_

sensor_msgs::CameraInfo ADI3DToFADTF31xx::cam_info_msg_
private

Definition at line 256 of file adi_3dtof_adtf31xx.h.

◆ camera_link_

std::string ADI3DToFADTF31xx::camera_link_
private

Definition at line 240 of file adi_3dtof_adtf31xx.h.

◆ conf_frame_

unsigned short* ADI3DToFADTF31xx::conf_frame_
private

Definition at line 260 of file adi_3dtof_adtf31xx.h.

◆ conf_image_publisher_

ros::Publisher ADI3DToFADTF31xx::conf_image_publisher_
private

Definition at line 263 of file adi_3dtof_adtf31xx.h.

◆ confidence_threshold_

int ADI3DToFADTF31xx::confidence_threshold_ = 10
private

Definition at line 247 of file adi_3dtof_adtf31xx.h.

◆ curr_frame_timestamp_

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

Definition at line 299 of file adi_3dtof_adtf31xx.h.

◆ depth_extrinsics_

CameraExtrinsics ADI3DToFADTF31xx::depth_extrinsics_
private

Definition at line 267 of file adi_3dtof_adtf31xx.h.

◆ depth_extrinsics_external_

CameraExtrinsics ADI3DToFADTF31xx::depth_extrinsics_external_
private

Definition at line 268 of file adi_3dtof_adtf31xx.h.

◆ depth_frame_

unsigned short* ADI3DToFADTF31xx::depth_frame_
private

Definition at line 257 of file adi_3dtof_adtf31xx.h.

◆ depth_image_publisher_

ros::Publisher ADI3DToFADTF31xx::depth_image_publisher_
private

Definition at line 261 of file adi_3dtof_adtf31xx.h.

◆ depth_info_publisher_

ros::Publisher ADI3DToFADTF31xx::depth_info_publisher_
private

Definition at line 265 of file adi_3dtof_adtf31xx.h.

◆ depth_intrinsics_

CameraIntrinsics ADI3DToFADTF31xx::depth_intrinsics_
private

Definition at line 266 of file adi_3dtof_adtf31xx.h.

◆ dynamic_reconfigure_callbacktype_

dynamic_reconfigure::Server<adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig>::CallbackType ADI3DToFADTF31xx::dynamic_reconfigure_callbacktype_
private

Definition at line 288 of file adi_3dtof_adtf31xx.h.

◆ dynamic_reconfigure_config_

adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig ADI3DToFADTF31xx::dynamic_reconfigure_config_
private

Definition at line 289 of file adi_3dtof_adtf31xx.h.

◆ enable_depth_ab_compression_

bool ADI3DToFADTF31xx::enable_depth_ab_compression_
private

Definition at line 245 of file adi_3dtof_adtf31xx.h.

◆ enable_point_cloud_publish_

bool ADI3DToFADTF31xx::enable_point_cloud_publish_ = false
private

Definition at line 255 of file adi_3dtof_adtf31xx.h.

◆ encoding_type_

std::string ADI3DToFADTF31xx::encoding_type_
private

Definition at line 254 of file adi_3dtof_adtf31xx.h.

◆ error_in_frame_read_

bool ADI3DToFADTF31xx::error_in_frame_read_ = false
private

Definition at line 277 of file adi_3dtof_adtf31xx.h.

◆ frame_number_

int ADI3DToFADTF31xx::frame_number_
private

Definition at line 244 of file adi_3dtof_adtf31xx.h.

◆ image_height_

int ADI3DToFADTF31xx::image_height_ = 1024
private

Definition at line 243 of file adi_3dtof_adtf31xx.h.

◆ image_proc_utils_

ImageProcUtils* ADI3DToFADTF31xx::image_proc_utils_
private

Definition at line 269 of file adi_3dtof_adtf31xx.h.

◆ image_width_

int ADI3DToFADTF31xx::image_width_ = 1024
private

Definition at line 242 of file adi_3dtof_adtf31xx.h.

◆ input_file_name_

std::string ADI3DToFADTF31xx::input_file_name_
private

Definition at line 252 of file adi_3dtof_adtf31xx.h.

◆ input_frames_queue_

std::queue<ADI3DToFADTF31xxFrameInfo*> ADI3DToFADTF31xx::input_frames_queue_
private

Definition at line 280 of file adi_3dtof_adtf31xx.h.

◆ input_sensor_

IInputSensor* ADI3DToFADTF31xx::input_sensor_
private

Definition at line 239 of file adi_3dtof_adtf31xx.h.

◆ input_sensor_ip_

std::string ADI3DToFADTF31xx::input_sensor_ip_
private

Definition at line 253 of file adi_3dtof_adtf31xx.h.

◆ input_sensor_mode_

int ADI3DToFADTF31xx::input_sensor_mode_
private

Definition at line 241 of file adi_3dtof_adtf31xx.h.

◆ input_thread_mtx_

boost::mutex ADI3DToFADTF31xx::input_thread_mtx_
private

Definition at line 275 of file adi_3dtof_adtf31xx.h.

◆ jblf_filter_size_

int ADI3DToFADTF31xx::jblf_filter_size_ = 7
private

Definition at line 249 of file adi_3dtof_adtf31xx.h.

◆ jblf_filter_state_

bool ADI3DToFADTF31xx::jblf_filter_state_ = true
private

Definition at line 248 of file adi_3dtof_adtf31xx.h.

◆ max_debug_queue_length_

int ADI3DToFADTF31xx::max_debug_queue_length_ = 10
private

Definition at line 282 of file adi_3dtof_adtf31xx.h.

◆ max_input_queue_length_

int ADI3DToFADTF31xx::max_input_queue_length_ = 10
private

Definition at line 279 of file adi_3dtof_adtf31xx.h.

◆ output_node_queue_

std::queue<ADI3DToFADTF31xxOutputInfo*> ADI3DToFADTF31xx::output_node_queue_
private

Definition at line 283 of file adi_3dtof_adtf31xx.h.

◆ output_thread_mtx_

boost::mutex ADI3DToFADTF31xx::output_thread_mtx_
private

Definition at line 274 of file adi_3dtof_adtf31xx.h.

◆ process_output_thread_abort_

bool ADI3DToFADTF31xx::process_output_thread_abort_ = false
private

Definition at line 271 of file adi_3dtof_adtf31xx.h.

◆ processing_scale_

int ADI3DToFADTF31xx::processing_scale_ = 2
private

This is the scale factor to scale the input image. The processing will happen on the scaled down image The topics and the output coordinates will correspond to the scaled image size.

Definition at line 298 of file adi_3dtof_adtf31xx.h.

◆ radial_filter_max_threshold_

int ADI3DToFADTF31xx::radial_filter_max_threshold_ = 10000
private

Definition at line 251 of file adi_3dtof_adtf31xx.h.

◆ radial_filter_min_threshold_

int ADI3DToFADTF31xx::radial_filter_min_threshold_ = 100
private

Definition at line 250 of file adi_3dtof_adtf31xx.h.

◆ read_input_thread_abort_

bool ADI3DToFADTF31xx::read_input_thread_abort_ = false
private

Definition at line 272 of file adi_3dtof_adtf31xx.h.

◆ server_

dynamic_reconfigure::Server<adi_3dtof_adtf31xx::ADTF31xxSensorParamsConfig> ADI3DToFADTF31xx::server_
private

Definition at line 286 of file adi_3dtof_adtf31xx.h.

◆ xyz_frame_

short* ADI3DToFADTF31xx::xyz_frame_
private

Definition at line 259 of file adi_3dtof_adtf31xx.h.

◆ xyz_image_publisher_

ros::Publisher ADI3DToFADTF31xx::xyz_image_publisher_
private

Definition at line 264 of file adi_3dtof_adtf31xx.h.


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


adi_3dtof_adtf31xx
Author(s):
autogenerated on Sat May 17 2025 02:12:30