Open kekeblom opened 3 years ago
how did you fix the problem?
I actually never figured out the issue and just used a different sensor by a different manufacturer that we happened to have at the office. Worked great!
I think I this same issue.
I see that it is caused when calling an OpenCV method.
sgbm_matcher = cv::StereoSGBM::create(0, 16, 3);
sgbm_matcher->setPreFilterCap(63); // SEG FAULTS at this line.
So could be be an OpenCV bug ?
How can I disabled the Disparity processor ? I dont need it.
Found a workaround atleast:
For me it turned out to be version check related code. I rebuilt the ros wrapper with gdb debugging and found these lines. Here are my git diffs to fix it:
diff --git a/src/mynteyed/internal/camera_p.cc b/src/mynteyed/internal/camera_p.cc
index df52c65..70790e4 100644
--- a/src/mynteyed/internal/camera_p.cc
+++ b/src/mynteyed/internal/camera_p.cc
@@ -287,8 +287,8 @@ void CameraPrivate::EnableProcessMode(const ProcessMode& mode) {
}
void CameraPrivate::EnableProcessMode(const std::int32_t& mode) {
- if (Version(1, 6) > descriptors_->firmware_version)
- motions_->EnableProcessMode(mode);
+ //if (Version(1, 6) > descriptors_->firmware_version)
+ // motions_->EnableProcessMode(mode);
}
bool CameraPrivate::IsImageInfoSupported() const {
diff --git a/wrappers/ros/src/mynteye_wrapper_d/src/mynteye_wrapper_nodelet.cc b/wrappers/ros/src/mynteye_wrapper_d/src/mynteye_wrapper_nodelet.cc
index 6e97687..99929b7 100755
--- a/wrappers/ros/src/mynteye_wrapper_d/src/mynteye_wrapper_nodelet.cc
+++ b/wrappers/ros/src/mynteye_wrapper_d/src/mynteye_wrapper_nodelet.cc
@@ -291,9 +291,12 @@ class MYNTEYEWrapperNodelet : public nodelet::Nodelet {
NODELET_INFO_STREAM(dashes);
params.dev_index = dev_index;
}
+ /*
spec_version = mynteye->GetDescriptors()->spec_version;
{
std::vector<StreamInfo> color_infos;
std::vector<StreamInfo> depth_infos;
mynteye->GetStreamInfos(dev_index, &color_infos, &depth_infos);
@@ -311,7 +314,7 @@ class MYNTEYEWrapperNodelet : public nodelet::Nodelet {
NODELET_INFO_STREAM(info.index << " | " << info);
}
NODELET_INFO_STREAM(dashes);
- }
+ }*/
pub_mesh_ = nh.advertise<visualization_msgs::Marker>("camera_mesh", 0 );
// where to get the mesh from
@@ -445,7 +448,7 @@ class MYNTEYEWrapperNodelet : public nodelet::Nodelet {
void openDevice() {
if (mynteye->IsOpened()) return;
// Set stream data callbacks
std::vector<ImageType> types{
ImageType::IMAGE_LEFT_COLOR,
@@ -749,9 +752,9 @@ class MYNTEYEWrapperNodelet : public nodelet::Nodelet {
void publishAlignImu(bool imu_sub,
bool imu_processed_sub, bool temp_sub) {
- if (spec_version <= Version(1, 0)) {
- timestampAlign();
- }
+ /*if (spec_version <= Version(1, 0)) {
+ timestampAlign();
+ }*/
if (imu_accel == nullptr || imu_gyro == nullptr) {
return;
This is a bandaid for sure but it got me going again. Now I run make ros and the result works just fine.
I installed the sdk and roswrapper using
make -j ros
. I'm running opencv 3.4.5 as suggested by the docs.When I
roslaunch mynt_eye_ros_wrapper mynteye.launch
, the node segfaults. When I hookup gdb and run backtrace after the crash, I get the stacktrace at the bottom. I.e. the error seems to be atdisparity_processor.cc:74
.I can run the the
get_depth
sample, so the device and sdk is somewhat working.I am running Ubuntu 20.04, which I realize is not officially supported, but would very much appreciate any help on this.
If there is anything I can do to help diagnose or narrow down the issue, please let me know.
Thanks!