Functions | Variables
node.cpp File Reference

ROS node for SICK 3DCS driver. More...

#include <sick_3vistort_driver/driver.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/PointCloud2.h>
#include <cv_bridge/cv_bridge.h>
#include <boost/thread.hpp>
#include <sensor_msgs/CameraInfo.h>
#include <std_msgs/ByteMultiArray.h>
Include dependency graph for node.cpp:

Go to the source code of this file.

Functions

void _on_new_subscriber ()
int main (int argc, char **argv)
void on_frame (const boost::shared_ptr< Driver_3DCS::Data > &data)
void on_new_subscriber_it (const image_transport::SingleSubscriberPublisher &pub)
void on_new_subscriber_ros (const ros::SingleSubscriberPublisher &pub)
void publish_frame (const Driver_3DCS::Data &data)
void thr_publish_frame ()

Variables

Driver_3DCS::Controlg_control = NULL
boost::shared_ptr
< Driver_3DCS::Data
g_data
std::string g_frame_id
boost::mutex g_mtx_data
ros::Publisher g_pub_camera_info
image_transport::Publisher g_pub_confidence
image_transport::Publisher g_pub_depth
image_transport::Publisher g_pub_intensity
ros::Publisher g_pub_ios
ros::Publisher g_pub_points
bool g_publish_all = false
 If true: prevents skipping of frames and publish everything, otherwise use newest data to publish to ROS world.
const uint16_t NARE_DISTANCE_VALUE = 0xffffU
 Distance code for data outside the TOF range.
const bool SUPPRESS_INVALID_POINTS = true
 Flag whether invalid points are to be replaced by NaN.

Detailed Description

ROS node for SICK 3DCS driver.

Note:
Copyright (c) TODO FILL IN YEAR HERE
Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)

ROS package name: sick_3vistort_driver
Author:
Author: Joshua Hampp
Date:
Date of creation: 05/21/2015

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

This program is free software: you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License LGPL as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License LGPL for more details.

You should have received a copy of the GNU Lesser General Public License LGPL along with this program. If not, see <http://www.gnu.org/licenses/>.

Definition in file node.cpp.


Function Documentation

Definition at line 247 of file node.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 264 of file node.cpp.

void on_frame ( const boost::shared_ptr< Driver_3DCS::Data > &  data)

Definition at line 87 of file node.cpp.

Definition at line 260 of file node.cpp.

Definition at line 256 of file node.cpp.

void publish_frame ( const Driver_3DCS::Data data)

Definition at line 103 of file node.cpp.

Definition at line 81 of file node.cpp.


Variable Documentation

Definition at line 71 of file node.cpp.

boost::shared_ptr<Driver_3DCS::Data> g_data

Definition at line 77 of file node.cpp.

std::string g_frame_id

Definition at line 72 of file node.cpp.

boost::mutex g_mtx_data

Definition at line 76 of file node.cpp.

Definition at line 70 of file node.cpp.

Definition at line 69 of file node.cpp.

Definition at line 69 of file node.cpp.

Definition at line 69 of file node.cpp.

Definition at line 70 of file node.cpp.

Definition at line 70 of file node.cpp.

bool g_publish_all = false

If true: prevents skipping of frames and publish everything, otherwise use newest data to publish to ROS world.

Definition at line 74 of file node.cpp.

const uint16_t NARE_DISTANCE_VALUE = 0xffffU

Distance code for data outside the TOF range.

Definition at line 68 of file node.cpp.

const bool SUPPRESS_INVALID_POINTS = true

Flag whether invalid points are to be replaced by NaN.

Definition at line 65 of file node.cpp.



sick_3vistort_driver
Author(s):
autogenerated on Thu Aug 4 2016 04:03:59