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


astra_camera
Author(s): Tim Liu
autogenerated on Wed Dec 16 2020 03:54:34