Closed meetgandhi-dev closed 6 months ago
Here is the output of top command:
analog@aditof:~$ top -H -p 623 -bn1
top - 07:49:11 up 11 min, 2 users, load average: 0.12, 0.36, 0.22
Threads: 5 total, 0 running, 5 sleeping, 0 stopped, 0 zombie
%Cpu(s): 0.0 us, 0.0 sy, 0.0 ni,100.0 id, 0.0 wa, 0.0 hi, 0.0 si, 0.0 st
MiB Mem : 2690.3 total, 2117.3 free, 364.3 used, 208.7 buff/cache
MiB Swap: 0.0 total, 0.0 free, 0.0 used. 2256.5 avail Mem
PID USER PR NI VIRT RES SHR S %CPU %MEM TIME+ COMMAND
623 analog 20 0 334420 25716 8400 S 0.0 0.9 1:28.18 tof-ros-node
628 analog 20 0 334420 25716 8400 S 0.0 0.9 0:24.39 tof-ros-node
629 analog 20 0 334420 25716 8400 S 0.0 0.9 0:14.78 tof-ros-node
630 analog 20 0 334420 25716 8400 S 0.0 0.9 0:14.36 tof-ros-node
631 analog 20 0 334420 25716 8400 S 0.0 0.9 0:17.07 tof-ros-node
Try running data_collect with sudo. From this in the log that does not seem to be the case now:
I20230602 07:02:53.316262 712 camera_itof.cpp:143] Initializing camera sh: 1: cannot create /sys/class/gpio/gpio122/value: Permission denied sh: 1: cannot create /sys/class/gpio/gpio122/value: Permission denied
Also, what is the serial number of you device? I want to make sure you are using the correct JSON file.
I'm not sure from where to get the serial number. Below are some details which might help:
Model:
analog@aditof:~$ cat /proc/device-tree/model
NXP i.MX8MPlus ADI TOF carrier + ADSD3500
Serial Number from dmesg running on host:
[520949.222919] usb 2-4: new SuperSpeed Gen 1 USB device number 3 using xhci_hcd
[520949.243309] usb 2-4: New USB device found, idVendor=0456, idProduct=a4a2, bcdDevice= 1.00
[520949.243312] usb 2-4: New USB device strings: Mfr=1, Product=2, SerialNumber=3
[520949.243314] usb 2-4: Product: ADI TOF USB Gadget
[520949.243315] usb 2-4: Manufacturer: Analog Devices Inc.
[520949.243316] usb 2-4: SerialNumber: 12345678
The serial number is usually on the device.
For example:
I'm still trying to look for the serial number (The sticker is not there on the device).
However, I found one instead of DV11-163
my device has CR-413
.
outraw.bin.zip I tried to capture the "raw data" of the last captured frame before ToFI compute gets stuck. Attaching it here in the zip.
@meetgandhi-eic Are you referring to the call in the code or the command line tool tofi compute depth? If the latter, can you also send the command line parameters you used.
I'm referring to the call in the code.
@meetgandhi-eic Let's start by aligning the firmware version with SDK version. Given that you are using SDK version 4.1.1, I would suggest updating the firmware to version 4.1.5. See the eval kit 4.1.1 release to get the firmware: https://github.com/analogdevicesinc/ToF/releases/tag/v4.1.1
Note, version v4.2.0 eval kit has also been released.
How did you save the data that was sent?
The serial number is usually on the device.
For example:
Okay. I get the mode table information from here According to the same, the current ToF serial number is starting from CR-xxx.
@meetgandhi-eic Let's start by aligning the firmware version with SDK version. Given that you are using SDK version 4.1.1, I would suggest updating the firmware to version 4.1.5. See the eval kit 4.1.1 release to get the firmware: https://github.com/analogdevicesinc/ToF/releases/tag/v4.1.1
Note, version v4.2.0 eval kit has also been released.
How did you save the data that was sent?
Hi, I have switched to SDK v4.2.0 and FW version 4.2.4. Here are some details for the same:
SHA256 for FW:
analog@aditof:~$ sha256sum Fw_Update_4.2.4.bin
d7a4c4c406080c9ecfb7760cadf626d2c3e5835dae70579e469fdfaa6a075613 Fw_Update_4.2.4.bin
SHA256 for libs: (~/Workspace/libs directory)
analog@aditof:~/Workspace/libs$ sha256sum *
48faff46c51b4ddc15d5c5f8c9795810c0b9ec7b6bf0eda19ecce24f6561ea03 libtofi_compute.so
3338039beca91b20992175a52f47a96372be0dedf564f76abadc4fa81862faf0 libtofi_config.so
002b0d97b888dbf85655b976e280cf861b2b5faf8ac29f152265996beb7a09dd tofi_compute_depth
SDK release:
analog@aditof:~/Workspace/ToF$ git status
HEAD detached at v4.2.0
nothing to commit, working tree clean
analog@aditof:~/Workspace/ToF$ git log -n 1
commit b260ad465698f38809b7114c05504a5d4bf2569b (HEAD, tag: v4.2.0)
Author: Dan Nechita <dan.nechita@analog.com>
Date: Fri May 26 17:16:20 2023 +0300
sdk: Swap expected values for width, height of mixed modes
Signed-off-by: Dan Nechita <dan.nechita@analog.com>
Here is the application code:
#include "aditof/aditof.h"
#include "aditof/sensor_enumerator_factory.h"
#include "aditof/sensor_enumerator_interface.h"
#include "aditof/camera.h"
#include <iostream>
#include <linux/videodev2.h>
#include <map>
#include <string>
#include <sys/time.h>
#include <vector>
#include <memory>
#include <chrono>
#include <fstream>
#include <glog/logging.h>
#include <thread>
#include <queue>
#include <mutex>
#include <stdlib.h>
#include <signal.h>
using std::chrono::duration_cast;
using std::chrono::milliseconds;
using std::chrono::steady_clock;
using std::chrono::time_point;
using std::chrono::time_point_cast;
using TimePoint = time_point<steady_clock, milliseconds>;
static inline TimePoint current_timepoint()
{
return (time_point_cast<milliseconds>(steady_clock::now()));
}
/* Available sensors */
using namespace aditof;
aditof::System tofSystem;
std::vector<std::shared_ptr<aditof::Camera>> cameras;
std::shared_ptr<aditof::Camera> depthCam;
std::queue<aditof::Frame *> framequeue;
std::mutex m_mtxQueue;
bool sensorStarted = false;
bool captureTimedout = false;
Status save_frame(aditof::Frame &frame, std::string frameType)
{
uint16_t *data1;
FrameDataDetails fDetails;
Status status = Status::OK;
status = frame.getData(frameType, &data1);
if (status != Status::OK)
{
LOG(ERROR) << "Could not get frame data " + frameType + "!";
return status;
}
if (!data1)
{
LOG(ERROR) << "no memory allocated in frame";
return status;
}
std::ofstream g("out_" + frameType + "_" + fDetails.type + ".bin",
std::ios::binary);
frame.getDataDetails(frameType, fDetails);
g.write((char *)data1, fDetails.width * fDetails.height * sizeof(uint16_t));
g.close();
return status;
}
static void sig_alarm_handler(int sig)
{
std::cerr << "inside Signal" << std::endl;
captureTimedout = true;
throw sig;
}
static void cleanup_sensors()
{
if (sensorStarted)
{
depthCam->stop();
sensorStarted = false;
}
cameras.clear();
}
static bool init_sensors(const std::string &configFile)
{
aditof::Status status;
tofSystem.getCameraList(cameras);
if (cameras.empty())
{
LOG(WARNING) << "No cameras found";
return false;
}
depthCam = cameras.front();
status = depthCam->setControl("initialization_config", configFile);
if (status != Status::OK)
{
LOG(ERROR) << "Failed to set control!";
return false;
}
status = depthCam->initialize();
if (status != Status::OK)
{
LOG(ERROR) << "Could not initialize camera!";
return false;
}
aditof::CameraDetails cameraDetails;
depthCam->getDetails(cameraDetails);
LOG(INFO) << "SD card image version: " << cameraDetails.sdCardImageVersion;
LOG(INFO) << "Kernel version: " << cameraDetails.kernelVersion;
LOG(INFO) << "U-Boot version: " << cameraDetails.uBootVersion;
std::vector<std::string> frameTypes;
depthCam->getAvailableFrameTypes(frameTypes);
if (frameTypes.empty())
{
LOG(ERROR) << "no frame type available!";
return false;
}
LOG(INFO) << "Availble frame types:";
for (auto item : frameTypes)
{
LOG(INFO) << item;
}
status = depthCam->setFrameType(frameTypes.at(0));
if (status != Status::OK)
{
LOG(ERROR) << "Could not set camera frame type!";
return false;
}
status = depthCam->start();
if (status != Status::OK)
{
LOG(ERROR) << "Could not start the camera!";
return false;
}
sensorStarted = true;
signal(SIGALRM, sig_alarm_handler);
return true;
}
void get_frames()
{
aditof::Status status;
aditof::Frame frame;
FrameDataDetails fDetails;
uint16_t *pData;
uint32_t nFrames = 0;
auto fpsTimeStamp = current_timepoint();
while (1)
{
try
{
alarm(5);
status = depthCam->requestFrame(&frame);
if (status != Status::OK)
{
LOG(ERROR) << "Could not request frame!";
return;
}
}
catch (...)
{
LOG(ERROR) << "signal caught";
save_frame(frame, "raw");
return;
}
++nFrames;
auto curTimeStamp = current_timepoint();
int32_t tExpiredTicks = duration_cast<milliseconds>(curTimeStamp - fpsTimeStamp).count();
if (tExpiredTicks > 1000)
{
LOG(ERROR) << "Fps " << nFrames;
fpsTimeStamp = curTimeStamp;
nFrames = 0;
}
}
}
int main(int argc, char *pArgv[])
{
google::InitGoogleLogging(pArgv[0]);
FLAGS_logtostderr = 1;
init_sensors(pArgv[1]);
get_frames();
cleanup_sensors();
return false;
}
logic:
I'm setting an alarm of 5 seconds (chosen randomly) before invoking depthCam->requestFrame(&frame)
. So, if the frame is successfully retrieved, it will try to capture the next frame which will cancel the previous timer and start a new.
Now, when it comes to a point where the execution gets stuck, the alarm will get triggered which will call the signal handler sig_alarm_handler
. From the signal handler, we are throwing an exception which forces the execution to come out of blockage and return it's control to catch block.
By the time we reach this point LOG(ERROR) << "signal caught";
we already have the raw frame captured and stored in the aditof::Frame frame;
variable. The same we are dumping in the file using save_frame
API.
Here are the logs which are coming from the application which is running:
root@aditof:/home/analog/multi-threaded-ros/build# ./tof-ros-node config/config_crosby_old_modes.json
I20230621 10:21:58.262485 2142 system_impl.cpp:90] SDK built with websockets version:3.1.0
I20230621 10:21:58.262882 2142 sensor_enumerator_imx.cpp:116] Looking for sensors on the target
I20230621 10:21:58.263294 2142 sensor_enumerator_imx.cpp:137] Looking at: /dev/media0 for an eligible TOF camera
I20230621 10:21:58.269107 2142 sensor_enumerator_imx.cpp:153] Considering: /dev/media0 an eligible TOF camera
W20230621 10:21:58.270377 2142 adsd3500_interrupt_notifier.cpp:57] Failed to open the debug sysfs. Interrupts support will not be available!
I20230621 10:21:58.271415 2142 camera_itof.cpp:146] Initializing camera
I20230621 10:21:58.271569 2142 adsd3500_sensor.cpp:207] Opening device
I20230621 10:21:58.271638 2142 adsd3500_sensor.cpp:225] Looking for the following cards:
I20230621 10:21:58.271672 2142 adsd3500_sensor.cpp:227] mxc-isi-cap
I20230621 10:21:58.271716 2142 adsd3500_sensor.cpp:239] device: /dev/video0 subdevice: /dev/v4l-subdev1
I20230621 10:21:58.281687 2142 adsd3500_sensor.cpp:335] ADSD3500 is ready to communicate with.
W20230621 10:21:58.291468 2142 adsd3500_sensor.cpp:1508] Failed to read imager type and CCB version (command 0x0032). Possibly command is not implemented on the current adsd3500 firmware.
W20230621 10:21:58.291568 2142 adsd3500_sensor.cpp:1516] Since the image type is unknown, fall back on compile flag to determine imager type
I20230621 10:21:58.300521 2142 mode_info.cpp:156] Using old modes table.
I20230621 10:21:58.300741 2142 mode_info.cpp:156] Using old modes table.
I20230621 10:21:58.366457 2142 camera_itof.cpp:355] Current adsd3500 firmware version is: 3.1.1.0
I20230621 10:21:58.366575 2142 camera_itof.cpp:357] Current adsd3500 firmware git hash is: 7e9902fd27bda6747d898db19fef7d9faf361a69
I20230621 10:21:58.366993 2142 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_mp.ini
I20230621 10:21:58.367125 2142 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_qmp.ini
I20230621 10:21:58.367185 2142 camera_itof.cpp:1777] Current Depth ini file is: ./config/RawToDepthAdsd3500_mp.ini
I20230621 10:21:58.369479 2142 camera_itof.cpp:450] Camera FPS set from Json file at: 30
I20230621 10:21:58.370474 2142 camera_itof.cpp:462] Camera initialized
I20230621 10:21:58.370609 2142 main.cpp:119] SD card image version: microsd-93635899.img
I20230621 10:21:58.370651 2142 main.cpp:120] Kernel version: lf-5.10.72-2.2.0
I20230621 10:21:58.370687 2142 main.cpp:121] U-Boot version: imx_v2020.04_5.4.70_2.3.0
I20230621 10:21:58.370769 2142 main.cpp:131] Availble frame types:
I20230621 10:21:58.370806 2142 main.cpp:134] qmp
I20230621 10:21:58.370841 2142 main.cpp:134] mp
I20230621 10:21:58.376678 2142 camera_itof.cpp:539] Chosen mode: qmp
I20230621 10:21:58.376785 2142 camera_itof.cpp:593] Using ini file: ./config/RawToDepthAdsd3500_qmp.ini
I20230621 10:21:58.382022 2142 adsd3500_sensor.cpp:207] Opening device
I20230621 10:21:58.382165 2142 adsd3500_sensor.cpp:225] Looking for the following cards:
I20230621 10:21:58.382220 2142 adsd3500_sensor.cpp:227] mxc-isi-cap
I20230621 10:21:58.382261 2142 adsd3500_sensor.cpp:239] device: /dev/video0 subdevice: /dev/v4l-subdev1
I20230621 10:21:58.382611 2142 adsd3500_sensor.cpp:463] Setting camera mode to qmp
I20230621 10:21:58.389932 2142 camera_itof.cpp:924] initComputeLibrary
I20230621 10:21:58.746026 2142 adsd3500_sensor.cpp:376] Starting device 0
E20230621 10:22:00.122727 2142 main.cpp:188] Fps 32
E20230621 10:22:01.147651 2142 main.cpp:188] Fps 31
E20230621 10:22:02.170399 2142 main.cpp:188] Fps 31
E20230621 10:22:03.193943 2142 main.cpp:188] Fps 31
E20230621 10:22:04.218647 2142 main.cpp:188] Fps 31
E20230621 10:22:05.240669 2142 main.cpp:188] Fps 31
inside Signal
E20230621 10:22:11.133399 2142 main.cpp:179] signal caught
I20230621 10:22:11.149775 2142 adsd3500_sensor.cpp:418] Stopping device
Observation:
@meetgandhi-eic just one note, the firmware is still: 3.1.1.0
I20230621 10:21:58.366457 2142 camera_itof.cpp:355] Current adsd3500 firmware version is: 3.1.1.0
Please also update the SD card image to the 4.2.0 image.
@meetgandhi-eic just one note, the firmware is still: 3.1.1.0
I20230621 10:21:58.366457 2142 camera_itof.cpp:355] Current adsd3500 firmware version is: 3.1.1.0
Please also update the SD card image to the 4.2.0 image.
Hi @andrestraker , I have received the ToF kit with newer version support. I tried running the application in "lr-qnative" mode. But got the same results. Here are the insights for the same for further debugging:
Application source code:
#include "aditof/aditof.h"
#include "aditof/sensor_enumerator_factory.h"
#include "aditof/sensor_enumerator_interface.h"
#include "aditof/camera.h"
#include <iostream>
#include <linux/videodev2.h>
#include <map>
#include <string>
#include <sys/time.h>
#include <vector>
#include <memory>
#include <chrono>
#include <fstream>
#include <glog/logging.h>
#include <thread>
#include <queue>
#include <mutex>
#include <stdlib.h>
#include <signal.h>
using std::chrono::duration_cast;
using std::chrono::milliseconds;
using std::chrono::steady_clock;
using std::chrono::time_point;
using std::chrono::time_point_cast;
using TimePoint = time_point<steady_clock, milliseconds>;
static inline TimePoint current_timepoint()
{
return (time_point_cast<milliseconds>(steady_clock::now()));
}
/* Available sensors */
using namespace aditof;
aditof::System tofSystem;
std::vector<std::shared_ptr<aditof::Camera>> cameras;
std::shared_ptr<aditof::Camera> depthCam;
std::queue<aditof::Frame *> framequeue;
std::mutex m_mtxQueue;
bool sensorStarted = false;
bool captureTimedout = false;
Status save_frame(aditof::Frame &frame, std::string frameType)
{
uint16_t *data1;
FrameDataDetails fDetails;
Status status = Status::OK;
status = frame.getData(frameType, &data1);
if (status != Status::OK)
{
LOG(ERROR) << "Could not get frame data " + frameType + "!";
return status;
}
if (!data1)
{
LOG(ERROR) << "no memory allocated in frame";
return status;
}
std::ofstream g("out_" + frameType + "_" + fDetails.type + ".bin",
std::ios::binary);
frame.getDataDetails(frameType, fDetails);
g.write((char *)data1, fDetails.width * fDetails.height * sizeof(uint16_t));
g.close();
return status;
}
static void sig_alarm_handler(int sig)
{
std::cerr << "inside Signal" << std::endl;
captureTimedout = true;
throw sig;
}
static void cleanup_sensors()
{
if (sensorStarted)
{
depthCam->stop();
sensorStarted = false;
}
LOG(WARNING) << __func__;
cameras.clear();
LOG(WARNING) << __func__;
}
static bool init_sensors(const std::string &configFile)
{
aditof::Status status;
tofSystem.getCameraList(cameras);
if (cameras.empty())
{
LOG(WARNING) << "No cameras found";
return false;
}
depthCam = cameras.front();
status = depthCam->setControl("initialization_config", configFile);
if (status != Status::OK)
{
LOG(ERROR) << "Failed to set control!";
return false;
}
status = depthCam->initialize();
if (status != Status::OK)
{
LOG(ERROR) << "Could not initialize camera!";
return false;
}
aditof::CameraDetails cameraDetails;
depthCam->getDetails(cameraDetails);
LOG(INFO) << "SD card image version: " << cameraDetails.sdCardImageVersion;
LOG(INFO) << "Kernel version: " << cameraDetails.kernelVersion;
LOG(INFO) << "U-Boot version: " << cameraDetails.uBootVersion;
std::vector<std::string> frameTypes;
depthCam->getAvailableFrameTypes(frameTypes);
if (frameTypes.empty())
{
LOG(ERROR) << "no frame type available!";
return false;
}
LOG(INFO) << "Availble frame types:";
for (auto item : frameTypes)
{
LOG(INFO) << item;
}
LOG(INFO) << "setting frame type " << frameTypes.at(3);
status = depthCam->setFrameType(frameTypes.at(3));
if (status != Status::OK)
{
LOG(ERROR) << "Could not set camera frame type!";
return false;
}
status = depthCam->start();
if (status != Status::OK)
{
LOG(ERROR) << "Could not start the camera!";
return false;
}
sensorStarted = true;
return true;
}
void get_frames()
{
aditof::Status status;
aditof::Frame frame;
FrameDataDetails fDetails;
uint16_t *pData;
uint32_t nFrames = 0;
auto fpsTimeStamp = current_timepoint();
while (1)
{
try
{
alarm(2);
status = depthCam->requestFrame(&frame);
if (status != Status::OK)
{
LOG(ERROR) << "Could not request frame!";
return;
}
}
catch (...)
{
LOG(ERROR) << "signal caught";
save_frame(frame, "raw");
return;
}
++nFrames;
auto curTimeStamp = current_timepoint();
int32_t tExpiredTicks = duration_cast<milliseconds>(curTimeStamp - fpsTimeStamp).count();
if (tExpiredTicks > 1000)
{
LOG(ERROR) << "Fps " << nFrames;
fpsTimeStamp = curTimeStamp;
nFrames = 0;
}
}
}
int main(int argc, char *pArgv[])
{
google::InitGoogleLogging(pArgv[0]);
FLAGS_logtostderr = 1;
signal(SIGALRM, sig_alarm_handler);
init_sensors(pArgv[1]);
get_frames();
cleanup_sensors();
return 0;
}
Logs coming after running the application on i.MX8:
analog@aditof:~/multi-threaded-ros/build$ ./tof-ros-node config/config_crosby_adsd3500_new_modes.json
I20230315 15:11:25.791796 995 system_impl.cpp:90] SDK built with websockets version:3.1.0
I20230315 15:11:25.792229 995 sensor_enumerator_imx.cpp:116] Looking for sensors on the target
I20230315 15:11:25.792629 995 sensor_enumerator_imx.cpp:137] Looking at: /dev/media0 for an eligible TOF camera
I20230315 15:11:25.804083 995 sensor_enumerator_imx.cpp:153] Considering: /dev/media0 an eligible TOF camera
W20230315 15:11:25.805563 995 adsd3500_interrupt_notifier.cpp:57] Failed to open the debug sysfs. Interrupts support will not be available!
I20230315 15:11:25.807426 995 camera_itof.cpp:146] Initializing camera
I20230315 15:11:25.807543 995 adsd3500_sensor.cpp:207] Opening device
I20230315 15:11:25.807619 995 adsd3500_sensor.cpp:225] Looking for the following cards:
I20230315 15:11:25.807659 995 adsd3500_sensor.cpp:227] mxc-isi-cap
I20230315 15:11:25.807711 995 adsd3500_sensor.cpp:239] device: /dev/video0 subdevice: /dev/v4l-subdev1
I20230315 15:11:25.818082 995 adsd3500_sensor.cpp:335] ADSD3500 is ready to communicate with.
I20230315 15:11:25.829485 995 mode_info.cpp:148] Using new modes table for adsd3500.
I20230315 15:11:25.838388 995 mode_info.cpp:144] Using new mixed modes table for adsd3500.
I20230315 15:11:25.838527 995 mode_info.cpp:144] Using new mixed modes table for adsd3500.
I20230315 15:11:26.067943 995 camera_itof.cpp:355] Current adsd3500 firmware version is: 4.2.4.0
I20230315 15:11:26.068078 995 camera_itof.cpp:357] Current adsd3500 firmware git hash is: 5ecd368683f2b49f6af7c872deaf04d5696206c4
I20230315 15:11:26.068621 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_lr-qnative.ini
I20230315 15:11:26.068756 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_lr-native.ini
I20230315 15:11:26.068814 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_sr-qnative.ini
I20230315 15:11:26.068861 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_sr-native.ini
I20230315 15:11:26.068912 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_sr-mixed.ini
I20230315 15:11:26.068959 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd3500_lr-mixed.ini
I20230315 15:11:26.069015 995 camera_itof.cpp:1766] Found Depth ini file: ./config/RawToDepthAdsd_pcm-native.ini
I20230315 15:11:26.069070 995 camera_itof.cpp:1777] Current Depth ini file is: ./config/RawToDepthAdsd3500_lr-mixed.ini
I20230315 15:11:26.071703 995 camera_itof.cpp:450] Camera FPS set from Json file at: 30
I20230315 15:11:26.072748 995 camera_itof.cpp:462] Camera initialized
I20230315 15:11:26.072893 995 main.cpp:121] SD card image version: microsd-4.2.0-b260ad46.img
I20230315 15:11:26.072942 995 main.cpp:122] Kernel version: lf-5.10.72-2.2.0
I20230315 15:11:26.072983 995 main.cpp:123] U-Boot version: imx_v2020.04_5.4.70_2.3.0
I20230315 15:11:26.073072 995 main.cpp:133] Availble frame types:
I20230315 15:11:26.073115 995 main.cpp:136] sr-native
I20230315 15:11:26.073156 995 main.cpp:136] lr-native
I20230315 15:11:26.073196 995 main.cpp:136] sr-qnative
I20230315 15:11:26.073235 995 main.cpp:136] lr-qnative
I20230315 15:11:26.073274 995 main.cpp:136] pcm-native
I20230315 15:11:26.073313 995 main.cpp:136] sr-mixed
I20230315 15:11:26.073352 995 main.cpp:136] lr-mixed
I20230315 15:11:26.073395 995 main.cpp:139] setting frame type lr-qnative
I20230315 15:11:26.078999 995 camera_itof.cpp:539] Chosen mode: lr-qnative
I20230315 15:11:26.079098 995 camera_itof.cpp:593] Using ini file: ./config/RawToDepthAdsd3500_lr-qnative.ini
I20230315 15:11:26.084233 995 adsd3500_sensor.cpp:207] Opening device
I20230315 15:11:26.084319 995 adsd3500_sensor.cpp:225] Looking for the following cards:
I20230315 15:11:26.084350 995 adsd3500_sensor.cpp:227] mxc-isi-cap
I20230315 15:11:26.084381 995 adsd3500_sensor.cpp:239] device: /dev/video0 subdevice: /dev/v4l-subdev1
I20230315 15:11:26.084568 995 adsd3500_sensor.cpp:463] Setting camera mode to lr-qnative
I20230315 15:11:26.091243 995 camera_itof.cpp:924] initComputeLibrary
I20230315 15:11:26.451723 995 adsd3500_sensor.cpp:376] Starting device 0
E20230315 15:11:27.819129 995 main.cpp:190] Fps 31
E20230315 15:11:28.842587 995 main.cpp:190] Fps 31
E20230315 15:11:29.866875 995 main.cpp:190] Fps 31
E20230315 15:11:30.886827 995 main.cpp:190] Fps 31
E20230315 15:11:31.911239 995 main.cpp:190] Fps 31
E20230315 15:11:32.934468 995 main.cpp:190] Fps 31
E20230315 15:11:33.958351 995 main.cpp:190] Fps 31
E20230315 15:11:34.980616 995 main.cpp:190] Fps 31
E20230315 15:11:36.003803 995 main.cpp:190] Fps 31
E20230315 15:11:37.029127 995 main.cpp:190] Fps 31
E20230315 15:11:38.051384 995 main.cpp:190] Fps 31
inside Signal
E20230315 15:11:40.382778 995 main.cpp:181] signal caught
I20230315 15:11:40.395229 995 adsd3500_sensor.cpp:418] Stopping device
W20230315 15:11:40.396850 995 main.cpp:87] cleanup_sensors
W20230315 15:11:40.396951 995 main.cpp:89] cleanup_sensors
config file content:
analog@aditof:~/multi-threaded-ros/build$ cat config/config_crosby_adsd3500_new_modes.json
{
"VAUX_POWER_VOLTAGE": "18",
"DEPTH_INI": "./config/RawToDepthAdsd3500_lr-qnative.ini;./config/RawToDepthAdsd3500_lr-native.ini;./config/RawToDepthAdsd3500_sr-qnative.ini;./config/RawToDepthAdsd3500_sr-native.ini;./config/RawToDepthAdsd3500_sr-mixed.ini;./config/RawToDepthAdsd3500_lr-mixed.ini;./config/RawToDepthAdsd_pcm-native.ini",
"FPS": "30",
"FSYNC_MODE": "1"
}
SHA256 sum for librarires:
analog@aditof:~/Workspace/libs$ sha256sum *
1fa67a96aa1ba73a05af9e9e568a5bd95d451ab4679b1ac28d3e4a04d43b1336 libtofi_compute.so
76ee21b4d6c9e2edd051fce04ad7315e7817cbacb59d568e9d11462a91666b4f libtofi_config.so
8b6c353d2090d012cedff1cfa056a98601ecdef9ff16ce54856894df0b73b375 tofi_compute_depth
As I mentioned earlier, it gets stuck on random interval. The current log indicates it got stuck after ~15 seconds of run.
Steps to reproduce the issue:
cd /home/analog/Workspace/ToF/build
cmake -DUSE_DEPTH_COMPUTE_STUBS=OFF ..
make
sudo make install
cd <above_direcotry>
mkdir build
cd build
cmake ..
make
tof-ros-node
application. Run the same with following command:export LD_LIBRARY_PATH=/opt/websockets/lib:/usr/local/lib:/home/analog/Workspace/libs
./tof-ros-node config/config_crosby_adsd3500_new_modes.json
Here is the cmakelist to build the binrary:
project(tof-ros)
cmake_minimum_required(VERSION 3.5)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_STANDARD_EXTENSIONS OFF)
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -Wall -Werror -Wpedantic")
set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -Wall -Werror -Wpedantic")
list(APPEND CMAKE_PREFIX_PATH "/usr/local/lib;/opt/glog;/opt/protobuf;/opt/websockets")
set(CMAKE_INSTALL_RPATH "/usr/local/lib;/opt/glog/lib;/opt/websockets/lib;/home/einfochips/data/cam_sync/libs")
add_executable(tof-ros-node)
link_directories(/home/einfochips/data/cam_sync/libs)
FILE(GLOB SRC_FILES *.cpp *.hpp *.c *.h)
target_sources(tof-ros-node PRIVATE ${SRC_FILES})
find_package(aditof REQUIRED)
find_package(Libwebsockets REQUIRED)
find_package(glog REQUIRED)
find_package(Protobuf REQUIRED)
target_include_directories(tof-ros-node PUBLIC "${ADITOF_INCLUDE_DIRS}")
target_include_directories(tof-ros-node PUBLIC "${LIBWEBSOCKETS_INCLUDE_DIRS}")
target_link_libraries(tof-ros-node "${ADITOF_LIBRARIES}")
target_link_libraries(tof-ros-node aditof)
target_link_libraries(tof-ros-node /home/analog/Workspace/libs/libtofi_compute.so)
target_link_libraries(tof-ros-node /home/analog/Workspace/libs/libtofi_config.so)
target_link_libraries(tof-ros-node websockets_shared)
target_link_libraries(tof-ros-node glog::glog)
target_link_libraries(tof-ros-node pthread)
Let me know if you need any additional infomration.
Hi,
I'm using SDK Release v4.1.1. We have created a test application based on first-frame example application to calculate FPS we received from ToF on NXP board. We observed that in some random scenario the execution of our application gets stuck. We added some logs into the SDK to determine the place and found that it gets stuck inside TofiCompute and never comes out of it.
We are using the pre-built libraries present in lib folder. The following are sha256 hashes for the same:
Below is the content of config files that we are using:
config_crosby_old_modes.json
RawToDepthAdsd3500_mp.ini
RawToDepthAdsd3500_qmp.ini
Here are the power-on logs of application from the SDK:
Let me know if any additional information is required.