openni2_frame_listener.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Julius Kammerl (jkammerl@willowgarage.com)
30  */
31 #include "OpenNI.h"
32 
35 
37 
38 #include <ros/ros.h>
39 
40 #define TIME_FILTER_LENGTH 15
41 
42 namespace openni2_wrapper
43 {
44 
46  callback_(0),
47  user_device_timer_(false),
48  timer_filter_(new OpenNI2TimerFilter(TIME_FILTER_LENGTH)),
49  prev_time_stamp_(0.0)
50 {
52 }
53 
55 {
56  user_device_timer_ = enable;
57 
59  timer_filter_->clear();
60 }
61 
62 void OpenNI2FrameListener::onNewFrame(openni::VideoStream& stream)
63 {
64  stream.readFrame(&m_frame);
65 
66  if (m_frame.isValid() && callback_)
67  {
68  sensor_msgs::ImagePtr image(new sensor_msgs::Image);
69 
70  ros::Time ros_now = ros::Time::now();
71 
72  if (!user_device_timer_)
73  {
74  image->header.stamp = ros_now;
75 
76  ROS_DEBUG("Time interval between frames: %.4f ms", (float)((ros_now.toSec()-prev_time_stamp_)*1000.0));
77 
78  prev_time_stamp_ = ros_now.toSec();
79  } else
80  {
81  uint64_t device_time = m_frame.getTimestamp();
82 
83  double device_time_in_sec = static_cast<double>(device_time)/1000000.0;
84  double ros_time_in_sec = ros_now.toSec();
85 
86  double time_diff = ros_time_in_sec-device_time_in_sec;
87 
88  timer_filter_->addSample(time_diff);
89 
90  double filtered_time_diff = timer_filter_->getMedian();
91 
92  double corrected_timestamp = device_time_in_sec+filtered_time_diff;
93 
94  image->header.stamp.fromSec(corrected_timestamp);
95 
96  ROS_DEBUG("Time interval between frames: %.4f ms", (float)((corrected_timestamp-prev_time_stamp_)*1000.0));
97 
98  prev_time_stamp_ = corrected_timestamp;
99  }
100 
101  image->width = m_frame.getWidth();
102  image->height = m_frame.getHeight();
103 
104  std::size_t data_size = m_frame.getDataSize();
105 
106  image->data.resize(data_size);
107  memcpy(&image->data[0], m_frame.getData(), data_size);
108 
109  image->is_bigendian = 0;
110 
111  const openni::VideoMode& video_mode = m_frame.getVideoMode();
112  switch (video_mode.getPixelFormat())
113  {
116  image->step = sizeof(unsigned char) * 2 * image->width;
117  break;
120  image->step = sizeof(unsigned char) * 2 * image->width;
121  break;
124  image->step = sizeof(unsigned char) * 2 * image->width;
125  break;
128  image->step = sizeof(unsigned char) * 2 * image->width;
129  break;
130 
132  image->encoding = sensor_msgs::image_encodings::RGB8;
133  image->step = sizeof(unsigned char) * 3 * image->width;
134  break;
136  image->encoding = sensor_msgs::image_encodings::YUV422;
137  image->step = sizeof(unsigned char) * 4 * image->width;
138  break;
140  image->encoding = sensor_msgs::image_encodings::MONO8;
141  image->step = sizeof(unsigned char) * 1 * image->width;
142  break;
144  image->encoding = sensor_msgs::image_encodings::MONO16;
145  image->step = sizeof(unsigned char) * 2 * image->width;
146  break;
148  default:
149  ROS_ERROR("Invalid image encoding");
150  break;
151  }
152 
153  callback_(image);
154  }
155 
156 }
157 
158 }
159 
boost::shared_ptr< OpenNI2TimerFilter > timer_filter_
#define TIME_FILTER_LENGTH
static void init()
const std::string TYPE_16UC1
const std::string MONO16
const std::string YUV422
static Time now()
#define ROS_ERROR(...)
void onNewFrame(openni::VideoStream &stream)
#define ROS_DEBUG(...)


openni2_camera
Author(s): Julius Kammerl
autogenerated on Fri Jun 7 2019 22:05:43