45 arInstallRequested_(
false),
46 depthFromMotion_(depthFromMotion)
64 std::vector<CameraConfig> & camera_configs,
67 if (camera_configs.empty()) {
71 int low_resolution_config_idx = 0;
72 int high_resolution_config_idx = 0;
73 int32_t smallest_height = camera_configs[0].height;
74 int32_t largest_height = camera_configs[0].height;
76 for (
int i = 1;
i < camera_configs.size(); ++
i) {
77 int32_t image_height = camera_configs[
i].height;
78 if (image_height < smallest_height) {
79 smallest_height = image_height;
80 low_resolution_config_idx =
i;
81 }
else if (image_height > largest_height) {
82 largest_height = image_height;
83 high_resolution_config_idx =
i;
87 if (low_resolution_config_idx == high_resolution_config_idx) {
88 *lowest_resolution_config = &camera_configs[low_resolution_config_idx];
90 *lowest_resolution_config = &camera_configs[low_resolution_config_idx];
91 *highest_resolution_config = &camera_configs[high_resolution_config_idx];
96 const ArSession* ar_session,
const ArCameraConfigList* all_configs,
97 int index,
int num_configs,
CameraConfig* camera_config) {
98 if (camera_config !=
nullptr && index >= 0 && index < num_configs) {
99 ArCameraConfig_create(ar_session, &camera_config->
config);
100 ArCameraConfigList_getItem(ar_session, all_configs, index,
102 ArCameraConfig_getImageDimensions(ar_session, camera_config->
config,
103 &camera_config->
width,
112 for (
int i = 0;
i < camera_configs.size(); ++
i) {
113 if (camera_configs[
i].
config !=
nullptr) {
114 ArCameraConfig_destroy(camera_configs[
i].
config);
132 ArInstallStatus install_status;
142 ArCoreApk_requestInstall(
env_,
activity_, user_requested_install, &install_status);
144 switch (install_status)
146 case AR_INSTALL_STATUS_INSTALLED:
148 case AR_INSTALL_STATUS_INSTALL_REQUESTED:
160 int32_t is_depth_supported = 0;
161 ArSession_isDepthModeSupported(
arSession_, AR_DEPTH_MODE_AUTOMATIC, &is_depth_supported);
166 if (is_depth_supported!=0) {
184 ArCameraConfigList* all_camera_configs =
nullptr;
186 ArCameraConfigList_create(
arSession_, &all_camera_configs);
188 ArCameraConfigFilter* camera_config_filter =
nullptr;
189 ArCameraConfigFilter_create(
arSession_, &camera_config_filter);
190 ArCameraConfigFilter_setTargetFps(
arSession_, camera_config_filter, AR_CAMERA_CONFIG_TARGET_FPS_30 | AR_CAMERA_CONFIG_TARGET_FPS_60);
191 ArSession_getSupportedCameraConfigsWithFilter(
arSession_, camera_config_filter, all_camera_configs);
192 ArCameraConfigList_getSize(
arSession_, all_camera_configs, &num_configs);
194 if (num_configs < 1) {
195 UERROR(
"No camera config found");
200 std::vector<CameraConfig> camera_configs;
201 CameraConfig* cpu_low_resolution_camera_config_ptr =
nullptr;
202 CameraConfig* cpu_high_resolution_camera_config_ptr =
nullptr;
203 camera_configs.resize(num_configs);
204 for (
int i = 0;
i < num_configs; ++
i) {
209 cpu_low_resolution_camera_config_ptr =
nullptr;
210 cpu_high_resolution_camera_config_ptr =
nullptr;
213 &cpu_low_resolution_camera_config_ptr,
214 &cpu_high_resolution_camera_config_ptr);
219 ArCameraConfigList_destroy(all_camera_configs);
220 ArSession_setCameraConfig(
arSession_, cpu_low_resolution_camera_config_ptr->
config);
228 if (ArSession_resume(
arSession_) != ArStatus::AR_SUCCESS)
230 UERROR(
"Cannot resume camera!");
282 int ret =
static_cast<int>(colorCameraToDisplayRotation) + 1;
287 ArSession_setDisplayGeometry(
arSession_,
ret, width, height);
306 glBindTexture(GL_TEXTURE_EXTERNAL_OES,
textureId_);
307 glTexParameteri(GL_TEXTURE_EXTERNAL_OES, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
308 glTexParameteri(GL_TEXTURE_EXTERNAL_OES, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
309 glTexParameteri(GL_TEXTURE_EXTERNAL_OES, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
310 glTexParameteri(GL_TEXTURE_EXTERNAL_OES, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
317 LOGE(
"CameraARCore::captureImage() ArSession_update error");
326 ArFrame_transformCoordinates2d(
338 ArCamera_getProjectionMatrix(
arSession_, ar_camera,
342 ArTrackingState camera_tracking_state;
343 ArCamera_getTrackingState(
arSession_, ar_camera, &camera_tracking_state);
346 if(camera_tracking_state == AR_TRACKING_STATE_TRACKING)
352 Transform poseArCore =
Transform(pose_raw[4], pose_raw[5], pose_raw[6], pose_raw[0], pose_raw[1], pose_raw[2], pose_raw[3]);
357 LOGE(
"CameraARCore: Pose is null");
369 LOGI(
"%f %f %f %f %d %d",
fx,
fy,
cx,
cy, width, height);
372 if(
fx > 0 &&
fy > 0 && width > 0 && height > 0 &&
cx > 0 &&
cy > 0)
376 ArPointCloud * pointCloud =
nullptr;
379 int32_t is_depth_supported = 0;
380 ArSession_isDepthModeSupported(
arSession_, AR_DEPTH_MODE_AUTOMATIC, &is_depth_supported);
382 ArImage * image =
nullptr;
384 if(status == AR_SUCCESS)
386 if(is_depth_supported)
388 LOGD(
"Acquire depth image!");
389 ArImage * depthImage =
nullptr;
394 if(
format == AR_IMAGE_FORMAT_DEPTH16)
396 LOGD(
"Depth format detected!");
398 ArImage_getNumberOfPlanes(
arSession_, depthImage, &planeCount);
399 LOGD(
"planeCount=%d", planeCount);
406 ArImage_getWidth(
arSession_, depthImage, &depth_width);
407 ArImage_getHeight(
arSession_, depthImage, &depth_height);
411 LOGD(
"width=%d, height=%d, bytes=%d stride=%d", depth_width, depth_height,
len,
stride);
413 cv::Mat occlusionImage = cv::Mat(depth_height, depth_width, CV_16UC1, (
void*)
data).clone();
415 float scaleX = (
float)depth_width / (
float)width;
416 float scaleY = (
float)depth_height / (
float)height;
420 ArImage_release(depthImage);
425 ArImage_getTimestamp(
arSession_, image, ×tamp_ns);
427 if(
format == AR_IMAGE_FORMAT_YUV_420_888)
431 ArImage_getNumberOfPlanes(
arSession_, image, &num_planes);
432 for(
int i=0;
i<num_planes; ++
i)
436 ArImage_getPlanePixelStride(
arSession_, image,
i, &pixel_stride);
437 ArImage_getPlaneRowStride(
arSession_, image,
i, &row_stride);
438 LOGI(
"Plane %d/%d: pixel stride=%d, row stride=%d",
i+1, num_planes, pixel_stride, row_stride);
444 ArImage_getPlaneData(
arSession_, image, 0, &plane_data, &data_length);
446 ArImage_getPlaneData(
arSession_, image, 2, &plane_uv_data, &uv_data_length);
448 if(plane_data !=
nullptr && data_length == height*width)
450 double stamp = double(timestamp_ns)/10e8;
452 LOGI(
"data_length=%d stamp=%f", data_length, stamp);
455 if((
long)plane_uv_data-(
long)plane_data != data_length)
458 cv::Mat yuv(height+height/2, width, CV_8UC1);
459 memcpy(yuv.data, plane_data, data_length);
460 memcpy(yuv.data+data_length, plane_uv_data, height/2*width);
461 cv::cvtColor(yuv, rgb, cv::COLOR_YUV2BGR_NV21);
465 cv::cvtColor(cv::Mat(height+height/2, width, CV_8UC1, (
void*)plane_data), rgb, cv::COLOR_YUV2BGR_NV21);
468 std::vector<cv::KeyPoint> kpts;
469 std::vector<cv::Point3f> kpts3;
474 ArPointCloud_getNumberOfPoints(
arSession_, pointCloud, &points);
475 const float * pointCloudData = 0;
476 ArPointCloud_getData(
arSession_, pointCloud, &pointCloudData);
478 LOGI(
"pointCloudData=%d size=%d", pointCloudData?1:0, points);
480 if(pointCloudData && points>0)
482 cv::Mat pointCloudDataMat(1, points, CV_32FC4, (
void *)pointCloudData);
485 LOGI(
"valid scan points = %d", scan.
size());
491 LOGI(
"pointCloud empty");
495 data.setFeatures(kpts, kpts3, cv::Mat());
505 LOGE(
"CameraARCore: cannot convert image format %d",
format);
510 LOGE(
"CameraARCore: failed to get rgb image (status=%d)", (
int)status);
513 ArImage_release(image);
514 ArPointCloud_release(pointCloud);
518 ArCamera_release(ar_camera);