Defines | Typedefs | Functions | Variables
sentis_tof_m100_node.cpp File Reference
#include <m100api.h>
#include <ros/console.h>
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <ros/publisher.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <stdio.h>
#include <time.h>
#include <sstream>
#include <sentis_tof_m100/sentis_tof_m100Config.h>
#include <dynamic_reconfigure/server.h>
Include dependency graph for sentis_tof_m100_node.cpp:

Go to the source code of this file.

Defines

#define Additive_Offset   1024
#define Average_Filter   2
#define FilterAverageConfig   0x01E2
#define FilterGaussConfig   0x01E3
#define FilterMedianConfig   0x01E1
#define FilterSLAFconfig   0x01E5
#define FPPN_Compensation   128
#define Gauss_Filter   4
#define ImgProcConfig   0x01E0
#define Median_Filter   1
#define ModFreq_Scaling   256
#define Scaling_DistCalibGradient   4096
#define Scaling_DistCalibOffset   8192
#define Scaling_MM   512
#define Sliding_Average   16
#define Temperature_Compensation   2048
#define Wiggling_Compensation   64

Typedefs

typedef pcl::PointCloud
< pcl::PointXYZI > 
PointCloud

Functions

void callback (sentis_tof_m100::sentis_tof_m100Config &config, uint32_t level)
int help ()
int initialize (int argc, char *argv[], ros::NodeHandle nh)
int main (int argc, char *argv[])
 Main function.
int publishData ()

Variables

bool additiveOffset
bool amplitudeFilterOn
float amplitudeThreshold
unsigned short averageConfig
int averageConfigIters
bool averageFilter
T_ERROR_CODE error
bool filterAverageConfigPixels
unsigned short filterConfig
bool filterGaussConfigPixels
bool first
bool FPPNCompensation
int frameRate
unsigned short gaussConfig
int gaussConfigIters
bool gaussFilter
T_SENTIS_HANDLE handle
T_SENTIS_DATA_HEADER header
int integrationTime
int medianConfigIters
bool medianFilter
bool modFreqScaling
int modulationFrequency
ros::Publisher pub_filtered
ros::Publisher pub_non_filtered
bool scalingDistCalibGradient
bool scalingDistCalibOffset
bool scalingMM
int SLAConfigWindows
bool slidingAverage
bool temperatureCompensation
bool wigglingCompensation

Define Documentation

#define Additive_Offset   1024

Definition at line 76 of file sentis_tof_m100_node.cpp.

#define Average_Filter   2

Definition at line 69 of file sentis_tof_m100_node.cpp.

#define FilterAverageConfig   0x01E2

Definition at line 63 of file sentis_tof_m100_node.cpp.

#define FilterGaussConfig   0x01E3

Definition at line 64 of file sentis_tof_m100_node.cpp.

#define FilterMedianConfig   0x01E1

Definition at line 62 of file sentis_tof_m100_node.cpp.

#define FilterSLAFconfig   0x01E5

Definition at line 65 of file sentis_tof_m100_node.cpp.

#define FPPN_Compensation   128

Definition at line 73 of file sentis_tof_m100_node.cpp.

#define Gauss_Filter   4

Definition at line 70 of file sentis_tof_m100_node.cpp.

#define ImgProcConfig   0x01E0

Definition at line 61 of file sentis_tof_m100_node.cpp.

#define Median_Filter   1

Definition at line 68 of file sentis_tof_m100_node.cpp.

#define ModFreq_Scaling   256

Definition at line 74 of file sentis_tof_m100_node.cpp.

#define Scaling_DistCalibGradient   4096

Definition at line 78 of file sentis_tof_m100_node.cpp.

#define Scaling_DistCalibOffset   8192

Definition at line 79 of file sentis_tof_m100_node.cpp.

#define Scaling_MM   512

Definition at line 75 of file sentis_tof_m100_node.cpp.

#define Sliding_Average   16

Definition at line 71 of file sentis_tof_m100_node.cpp.

#define Temperature_Compensation   2048

Definition at line 77 of file sentis_tof_m100_node.cpp.

#define Wiggling_Compensation   64

Definition at line 72 of file sentis_tof_m100_node.cpp.


Typedef Documentation

typedef pcl::PointCloud<pcl::PointXYZI> PointCloud

Definition at line 81 of file sentis_tof_m100_node.cpp.


Function Documentation

void callback ( sentis_tof_m100::sentis_tof_m100Config &  config,
uint32_t  level 
)

Definition at line 158 of file sentis_tof_m100_node.cpp.

int help ( )

Definition at line 119 of file sentis_tof_m100_node.cpp.

int initialize ( int  argc,
char *  argv[],
ros::NodeHandle  nh 
)

Initialize the camera and initial parameter values. Returns 1 if properly initialized.

Definition at line 327 of file sentis_tof_m100_node.cpp.

int main ( int  argc,
char *  argv[] 
)

Main function.

Parameters:
[in]int
[in]char*

Definition at line 779 of file sentis_tof_m100_node.cpp.

int publishData ( )

Publish the data based on set up parameters.

Definition at line 695 of file sentis_tof_m100_node.cpp.


Variable Documentation

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 94 of file sentis_tof_m100_node.cpp.

Definition at line 95 of file sentis_tof_m100_node.cpp.

unsigned short averageConfig

Definition at line 97 of file sentis_tof_m100_node.cpp.

Definition at line 103 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

T_ERROR_CODE error

Definition at line 110 of file sentis_tof_m100_node.cpp.

Definition at line 102 of file sentis_tof_m100_node.cpp.

unsigned short filterConfig

Definition at line 97 of file sentis_tof_m100_node.cpp.

Definition at line 102 of file sentis_tof_m100_node.cpp.

bool first

Definition at line 105 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

int frameRate

Definition at line 92 of file sentis_tof_m100_node.cpp.

unsigned short gaussConfig

Definition at line 97 of file sentis_tof_m100_node.cpp.

Definition at line 103 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

T_SENTIS_HANDLE handle

Camera Driver Parameters

Definition at line 109 of file sentis_tof_m100_node.cpp.

T_SENTIS_DATA_HEADER header

Definition at line 111 of file sentis_tof_m100_node.cpp.

Global Parameter Declarations Camera Configuration Parameters

Definition at line 90 of file sentis_tof_m100_node.cpp.

Definition at line 103 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 91 of file sentis_tof_m100_node.cpp.

Definition at line 117 of file sentis_tof_m100_node.cpp.

ROS Parameters

Definition at line 116 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

bool scalingMM

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 103 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.

Definition at line 99 of file sentis_tof_m100_node.cpp.



sentis_tof_m100
Author(s): Angel Merino , Simon Vogl
autogenerated on Sat Jun 8 2019 19:05:27