CameraAREngine.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "CameraAREngine.h"
29 #include "util.h"
33 #include "rtabmap/core/util2d.h"
34 
35 #include <media/NdkImage.h>
36 
37 namespace rtabmap {
38 
39 
41 // CameraAREngine
43 CameraAREngine::CameraAREngine(void* env, void* context, void* activity, bool smoothing):
44  CameraMobile(smoothing),
45  env_(env),
46  context_(context),
47  activity_(activity),
48  arInstallRequested_(false)
49 {
50  glGenTextures(1, &textureId_);
51 }
52 
54  // Disconnect ARCore service
55  close();
56 
57  glDeleteTextures(1, &textureId_);
58 }
59 
60 std::string CameraAREngine::getSerial() const
61 {
62  return "AREngine";
63 }
64 
65 bool CameraAREngine::init(const std::string & calibrationFolder, const std::string & cameraName)
66 {
67  close();
68 
70 
71  HwArInstallStatus install_status;
72  // If install was not yet requested, that means that we are resuming the
73  // activity first time because of explicit user interaction (such as
74  // launching the application)
75  bool user_requested_install = !arInstallRequested_;
76 
77  // === ATTENTION! ATTENTION! ATTENTION! ===
78  // This method can and will fail in user-facing situations. Your
79  // application must handle these cases at least somewhat gracefully. See
80  // HelloAR Java sample code for reasonable behavior.
81  HwArEnginesApk_requestInstall(env_, activity_, user_requested_install, &install_status);
82 
83  switch (install_status)
84  {
85  case HWAR_INSTALL_STATUS_INSTALLED:
86  break;
87  case HWAR_INSTALL_STATUS_INSTALL_REQUESTED:
88  arInstallRequested_ = true;
89  return false;
90  }
91 
92  // === ATTENTION! ATTENTION! ATTENTION! ===
93  // This method can and will fail in user-facing situations. Your
94  // application must handle these cases at least somewhat gracefully. See
95  // HelloAR Java sample code for reasonable behavior.
96  UASSERT(HwArSession_create(env_, context_, &arSession_) == HWAR_SUCCESS);
98 
99  HwArConfig_create(arSession_, &arConfig_);
101 
102  HwArConfig_setFocusMode(arSession_, arConfig_, HWAR_FOCUS_MODE_FIXED);
103  UASSERT(HwArSession_configure(arSession_, arConfig_) == HWAR_SUCCESS);
104 
105  HwArFrame_create(arSession_, &arFrame_);
106  UASSERT(arFrame_);
107 
108  HwArCameraIntrinsics_create(arSession_, &arCameraIntrinsics_); // May fail?!
109  //UASSERT(arCameraIntrinsics_);
110 
111  HwArPose_create(arSession_, nullptr, &arPose_);
112  UASSERT(arPose_);
113 
116  HwArConfig_setUpdateMode(arSession_, arConfig_, HWAR_UPDATE_MODE_BLOCKING);
117 
119 
120  // Required as ArSession_update does some off-screen OpenGL stuff...
121  HwArSession_setCameraTextureName(arSession_, textureId_);
122 
123  if (HwArSession_resume(arSession_) != HWAR_SUCCESS)
124  {
125  UERROR("Cannot resume camera!");
126  // In a rare case (such as another camera app launching) the camera may be
127  // given to a different app and so may not be available to this app. Handle
128  // this properly and recreate the session at the next iteration.
129  close();
130  return false;
131  }
132 
133  return true;
134 }
135 
137 {
139  if (arCameraIntrinsics_ != nullptr)
140  {
141  HwArCameraIntrinsics_destroy(arSession_, arCameraIntrinsics_);
142  }
143  arCameraIntrinsics_ = nullptr;
144 
145  if(arSession_!= nullptr)
146  {
147  HwArSession_destroy(arSession_);
148  }
149  arSession_ = nullptr;
150 
151  if(arConfig_!= nullptr)
152  {
153  HwArConfig_destroy(arConfig_);
154  }
155  arConfig_ = nullptr;
156 
157  if (arFrame_ != nullptr)
158  {
159  HwArFrame_destroy(arFrame_);
160  }
161  arFrame_ = nullptr;
162 
163  if (arPose_ != nullptr)
164  {
165  HwArPose_destroy(arPose_);
166  }
167  arPose_ = nullptr;
168 
170 }
171 
173 {
175  //LOGI("Capturing image...");
176 
178  if(!arSession_)
179  {
180  return data;
181  }
182 
183  // Update session to get current frame and render camera background.
184  if (HwArSession_update(arSession_, arFrame_) != HWAR_SUCCESS) {
185  LOGE("CameraAREngine::captureImage() ArSession_update error");
186  return data;
187  }
188 
189  HwArCamera* ar_camera;
190  HwArFrame_acquireCamera(arSession_, arFrame_, &ar_camera);
191 
192  HwArTrackingState camera_tracking_state;
193  HwArCamera_getTrackingState(arSession_, ar_camera, &camera_tracking_state);
194 
195  Transform pose;
196  if(camera_tracking_state == HWAR_TRACKING_STATE_TRACKING)
197  {
198  // pose in OpenGL coordinates
199  float pose_raw[7];
200  HwArCamera_getPose(arSession_, ar_camera, arPose_);
201  HwArPose_getPoseRaw(arSession_, arPose_, pose_raw);
202  pose = Transform(pose_raw[4], pose_raw[5], pose_raw[6], pose_raw[0], pose_raw[1], pose_raw[2], pose_raw[3]);
203 
204  // Get calibration parameters
205  // FIXME: Hard-coded as getting intrinsics with the api fails
206  float fx=492.689667,fy=492.606201, cx=323.594849, cy=234.659744;
207  int32_t camWidth=640, camHeight=480;
208  //HwArCamera_getImageIntrinsics(arSession_, ar_camera, arCameraIntrinsics_);
209  //HwArCameraIntrinsics_getFocalLength(arSession_, arCameraIntrinsics_, &fx, &fy);
210  //HwArCameraIntrinsics_getPrincipalPoint(arSession_, arCameraIntrinsics_, &cx, &cy);
211  //HwArCameraIntrinsics_getImageDimensions(arSession_, arCameraIntrinsics_, &camWidth, &camHeight);
212  LOGI("%f %f %f %f %d %d", fx, fy, cx, cy, camWidth, camHeight);
213 
214  if(fx > 0 && fy > 0 && camWidth > 0 && camHeight > 0 && cx > 0 && cy > 0)
215  {
216  //ArPointCloud * point_cloud;
217  //ArFrame_acquirePointCloud(ar_session_, ar_frame_, &point_cloud);
218 
219  HwArImage * image = nullptr;
220  HwArImage * depthImage = nullptr;
221  HwArStatus statusRgb = HwArFrame_acquireCameraImage(arSession_, arFrame_, &image);
222  HwArStatus statusDepth = HwArFrame_acquireDepthImage(arSession_, arFrame_, &depthImage);
223  if(statusRgb == HWAR_SUCCESS && statusDepth == HWAR_SUCCESS)
224  {
225  int64_t timestamp_ns;
226  HwArFrame_getTimestamp(arSession_, arFrame_, &timestamp_ns);
227 
228  int planeCount;
229  uint8_t *imageData = nullptr;
230  int len = 0;
231  int stride;
232  int width;
233  int height;
234  const AImage* ndkImageRGB;
235  HwArImage_getNdkImage(image, &ndkImageRGB);
236 
237  AImage_getNumberOfPlanes(ndkImageRGB, &planeCount);
238  AImage_getWidth(ndkImageRGB, &width);
239  AImage_getHeight(ndkImageRGB, &height);
240  AImage_getPlaneRowStride(ndkImageRGB, 0, &stride);
241  AImage_getPlaneData(ndkImageRGB, 0, &imageData, &len);
242  LOGI("RGB: width=%d, height=%d, bytes=%d stride=%d planeCount=%d", width, height, len, stride, planeCount);
243 
244  cv::Mat outputRGB;
245  if(imageData != nullptr && len>0)
246  {
247  cv::cvtColor(cv::Mat(height+height/2, width, CV_8UC1, (void*)imageData), outputRGB, cv::COLOR_YUV2BGR_NV21);
248  }
249 
250  //Depth
251  const AImage* ndkImageDepth;
252  HwArImage_getNdkImage(depthImage, &ndkImageDepth);
253  AImage_getNumberOfPlanes(ndkImageDepth, &planeCount);
254  AImage_getWidth(ndkImageDepth, &width);
255  AImage_getHeight(ndkImageDepth, &height);
256  AImage_getPlaneRowStride(ndkImageDepth, 0, &stride);
257  AImage_getPlaneData(ndkImageDepth, 0, &imageData, &len);
258  LOGI("Depth: width=%d, height=%d, bytes=%d stride=%d planeCount=%d", width, height, len, stride, planeCount);
259 
260  cv::Mat outputDepth(height, width, CV_16UC1);
261  uint16_t *dataShort = (uint16_t *)imageData;
262  for (int y = 0; y < outputDepth.rows; ++y)
263  {
264  for (int x = 0; x < outputDepth.cols; ++x)
265  {
266  uint16_t depthSample = dataShort[y*outputDepth.cols + x];
267  uint16_t depthRange = (depthSample & 0x1FFF); // first 3 bits are confidence
268  outputDepth.at<uint16_t>(y,x) = depthRange;
269  }
270  }
271 
272  if(!outputRGB.empty() && !outputDepth.empty())
273  {
274  double stamp = double(timestamp_ns)/10e8;
275  CameraModel model = CameraModel(fx, fy, cx, cy, deviceTColorCamera_, 0, cv::Size(camWidth, camHeight));
276  data = SensorData(outputRGB, outputDepth, model, 0, stamp);
277  }
278  }
279  else
280  {
281  LOGE("CameraAREngine: failed to get rgb image (status=%d %d)", (int)statusRgb, (int)statusDepth);
282  }
283 
284  HwArImage_release(image);
285  HwArImage_release(depthImage);
286  }
287  else
288  {
289  LOGE("Invalid intrinsics!");
290  }
291  }
292 
293  HwArCamera_release(ar_camera);
294 
295  if(pose.isNull())
296  {
297  LOGE("CameraAREngine: Pose is null");
298  }
299  else
300  {
302  this->poseReceived(pose);
303  // adjust origin
304  if(!getOriginOffset().isNull())
305  {
306  pose = getOriginOffset() * pose;
307  }
308  info->odomPose = pose;
309  }
310  return data;
311 
312 }
313 
315 {
317  //LOGI("Capturing image...");
318 
320  if(!arSession_)
321  {
322  return;
323  }
324 
325  // Update session to get current frame and render camera background.
326  if (HwArSession_update(arSession_, arFrame_) != HWAR_SUCCESS) {
327  LOGE("CameraARCore::captureImage() ArSession_update error");
328  return;
329  }
330 
331  HwArCamera* ar_camera;
332  HwArFrame_acquireCamera(arSession_, arFrame_, &ar_camera);
333 
334  HwArTrackingState camera_tracking_state;
335  HwArCamera_getTrackingState(arSession_, ar_camera, &camera_tracking_state);
336 
337  Transform pose;
339  if(camera_tracking_state == HWAR_TRACKING_STATE_TRACKING)
340  {
341  // pose in OpenGL coordinates
342  float pose_raw[7];
343  HwArCamera_getPose(arSession_, ar_camera, arPose_);
344  HwArPose_getPoseRaw(arSession_, arPose_, pose_raw);
345  pose = Transform(pose_raw[4], pose_raw[5], pose_raw[6], pose_raw[0], pose_raw[1], pose_raw[2], pose_raw[3]);
346  if(!pose.isNull())
347  {
349  this->poseReceived(pose);
350  }
351  }
352 
353  HwArCamera_release(ar_camera);
354 }
355 
356 } /* namespace rtabmap */
const Transform & getOriginOffset() const
Definition: CameraMobile.h:99
detail::int64 int64_t
Definition: fwd.hpp:311
x
data
static const rtabmap::Transform rtabmap_world_T_opengl_world(0.0f, 0.0f,-1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f)
virtual void capturePoseOnly()
#define LOGE(...)
void poseReceived(const Transform &pose)
detail::uint16 uint16_t
Definition: fwd.hpp:912
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
detail::uint8 uint8_t
Definition: fwd.hpp:908
#define UASSERT(condition)
HwArCameraIntrinsics * arCameraIntrinsics_
Transform deviceTColorCamera_
Definition: CameraMobile.h:133
static const rtabmap::Transform opengl_world_T_rtabmap_world(0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
#define LOGI(...)
bool isNull() const
Definition: Transform.cpp:107
#define false
Definition: ConvertUTF.c:56
virtual std::string getSerial() const
detail::int32 int32_t
Definition: fwd.hpp:307
HwArSession * arSession_
static const rtabmap::Transform opticalRotation
Definition: CameraMobile.h:76
#define UERROR(...)
ULogger class and convenient macros.
virtual SensorData captureImage(CameraInfo *info=0)
model
Definition: trace.py:4
CameraAREngine(void *env, void *context, void *activity, bool smoothing=false)
virtual void close()
Transform odomPose
Definition: CameraInfo.h:69


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:27