rpng / open_vins

An open source platform for visual-inertial navigation research.
https://docs.openvins.com
GNU General Public License v3.0
2.06k stars 616 forks source link

Multicamera setup #327

Closed EhrazImam closed 1 year ago

EhrazImam commented 1 year ago

Hi @goldbattle as you mentioned over here https://github.com/rpng/open_vins/issues/310#issuecomment-1510420888 can you help me with more details as i am interested to make it work with real hardware. Is it just supported in simulation. And i did followed your instruction to made some changes in https://github.com/rpng/open_vins/issues/285#issuecomment-1322613292


// Logic for sync stereo subscriber with 4 cameras
if (_app->get_params().state_options.num_cameras == 4) {
    // Read in the topics
    std::string cam_topic0, cam_topic1, cam_topic2, cam_topic3;
    _nh->param<std::string>("topic_camera" + std::to_string(0), cam_topic0, "/cam" + std::to_string(0) + "/image_raw");
    _nh->param<std::string>("topic_camera" + std::to_string(1), cam_topic1, "/cam" + std::to_string(1) + "/image_raw");
    _nh->param<std::string>("topic_camera" + std::to_string(2), cam_topic2, "/cam" + std::to_string(2) + "/image_raw");
    _nh->param<std::string>("topic_camera" + std::to_string(3), cam_topic3, "/cam" + std::to_string(3) + "/image_raw");

    parser->parse_external("relative_config_imucam", "cam" + std::to_string(0), "rostopic", cam_topic0);
    parser->parse_external("relative_config_imucam", "cam" + std::to_string(1), "rostopic", cam_topic1);
    parser->parse_external("relative_config_imucam", "cam" + std::to_string(2), "rostopic", cam_topic2);
    parser->parse_external("relative_config_imucam", "cam" + std::to_string(3), "rostopic", cam_topic3);

    // Create sync filter
    auto image_sub0 = std::make_shared<message_filters::Subscriber<sensor_msgs::Image>>(*_nh, cam_topic0, 1);
    auto image_sub1 = std::make_shared<message_filters::Subscriber<sensor_msgs::Image>>(*_nh, cam_topic1, 1);
    auto image_sub2 = std::make_shared<message_filters::Subscriber<sensor_msgs::Image>>(*_nh, cam_topic2, 1);
    auto image_sub3 = std::make_shared<message_filters::Subscriber<sensor_msgs::Image>>(*_nh, cam_topic3, 1);

    auto sync = std::make_shared<message_filters::Synchronizer<sync_pol>>(sync_pol(10), *image_sub0, *image_sub1, *image_sub2, *image_sub3);
    sync->registerCallback(boost::bind(&ROS1Visualizer::callback_quad, this, _1, _2, _3, _4, 0, 1, 2, 3));

    // Append to our vector of subscribers
    sync_cam.push_back(sync);
    sync_subs_cam.push_back(image_sub0);
    sync_subs_cam.push_back(image_sub1);
    sync_subs_cam.push_back(image_sub2);
    sync_subs_cam.push_back(image_sub3);

    PRINT_DEBUG("subscribing to cam (quad): %s\n", cam_topic0.c_str());
    PRINT_DEBUG("subscribing to cam (quad): %s\n", cam_topic1.c_str());
    PRINT_DEBUG("subscribing to cam (quad): %s\n", cam_topic2.c_str());
    PRINT_DEBUG("subscribing to cam (quad): %s\n", cam_topic3.c_str());

} else {
    // Add non-stereo callbacks for
}

Do i need to do more changes or something add-on

goldbattle commented 1 year ago

Yes this should likely work, but right now we consider that all cameras are synchronised (only a single time offset between the IMU and the camera set). If this is the case, then what you have should work. Additionally, you will likely need to edit the trackers to explicitly call either monocular tracking on each camera, or stereo tracking between any stereo pairs. I think things should work with more than 2 cameras if you set the use_stereo to false

https://github.com/rpng/open_vins/blob/74a63cf758f595cc280f2165e5a6576e7ef8521d/ov_core/src/track/TrackKLT.cpp#L78-L93

You could write something like the following:

// track a stereo pair (first two in message) then the rest
if (num_images == 4) {
    feed_stereo(message, 0, 1);
    parallel_for_(cv::Range(2, (int)num_images), LambdaBody([&](const cv::Range &range) {
                    for (int i = range.start; i < range.end; i++) {
                      feed_monocular(message, i);
                    }
                  }));
}
EhrazImam commented 1 year ago

@goldbattle thankyou for your reply. The camera setup that i am using are all synchronized, where out of 1 stereo pair and 2 are mono. So i need to do more changes with this setup.

goldbattle commented 1 year ago

If you just want to do mono tracking (independent), then you shouldn't need to. But to do a specific stereo pair, you will need to make edits similar to the ones I have suggested.

EhrazImam commented 1 year ago

@goldbattle I did the changes in ROS1Visualizer.cpp and ROS1Visualizer.h but i am getting this issue

catkin_ws/src/open_vins/ov_msckf/src/ros/ROS1Visualizer.cpp:182:105: required from here /usr/include/boost/bind/bind.hpp:833:35: error: no match for call to ‘(boost::mfi::mf8<void, ov_msckf::ROS1Visualizer, const boost::shared_ptr<const sensor_msgs::Image<std::allocator > >&, const boost::shared_ptr<const sensormsgs::Image<std::allocator > >&, const boost::shared_ptr<const sensormsgs::Image<std::allocator > >&, const boost::shared_ptr<const sensormsgs::Image<std::allocator > >&, int, int, int, int>) (ov_msckf::ROS1Visualizer*&, const boost::shared_ptr<const sensormsgs::Image<std::allocator > >&, const boost::shared_ptr<const sensormsgs::Image<std::allocator > >&, const boost::shared_ptr&, const boost::shared_ptr&, int&, int&, int&, int&)’ 833 | unwrapper::unwrap(f, 0)(a[basetype::a1], a[basetype::a2], a[basetype::a3], a[basetype::a4], a[basetype::a5], a[basetype::a6], a[basetype::a7], a[basetype::a8], a[basetype::a9]); | ~~~^~~~~~~~~~~~

goldbattle commented 1 year ago

I recommend googling. If I remember correctly, there is an upper limit to the number of parameters a function can take with the callback. So I suggest removing the int variables if you still have those.