Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/nodelet'
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Sep 23, 2024
2 parents 21439be + 995a889 commit 8f10396
Show file tree
Hide file tree
Showing 6 changed files with 189 additions and 61 deletions.
2 changes: 2 additions & 0 deletions ov_msckf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@ if (NOT OpenCV_FOUND)
endif ()
find_package(Boost REQUIRED COMPONENTS system filesystem thread date_time)
find_package(Ceres REQUIRED)
find_package(nodelet REQUIRED)

message(STATUS "OPENCV: " ${OpenCV_VERSION} " | BOOST: " ${Boost_VERSION} " | CERES: " ${Ceres_VERSION})

# If we will compile with aruco support
Expand Down
11 changes: 8 additions & 3 deletions ov_msckf/cmake/ROS1.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -121,9 +121,14 @@ if (catkin_FOUND AND ENABLE_ROS)
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

add_executable(run_subscribe_msckf src/run_subscribe_msckf.cpp)
target_link_libraries(run_subscribe_msckf ov_msckf_lib ${thirdparty_libraries})
install(TARGETS run_subscribe_msckf
add_library(RunSubscribeMsckf src/run_subscribe_msckf.cpp)
target_link_libraries(RunSubscribeMsckf
ov_msckf_lib
${catkin_LIBRARIES}
)
# add_executable(run_subscribe_msckf src/run_subscribe_msckf.cpp)
# target_link_libraries(run_subscribe_msckf ov_msckf_lib ${thirdparty_libraries})
install(TARGETS RunSubscribeMsckf
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
Expand Down
4 changes: 4 additions & 0 deletions ov_msckf/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
<depend condition="$ROS_VERSION == 1">cv_bridge</depend>
<depend condition="$ROS_VERSION == 1">ov_core</depend>
<depend condition="$ROS_VERSION == 1">ov_init</depend>
<depend condition="$ROS_VERSION == 1">nodelet</depend>

<!-- ROS2: Dependencies needed to compile this package. -->
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>
Expand Down Expand Up @@ -62,8 +63,11 @@
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
<rosdoc config="rosdoc.yaml" />
<nodelet plugin="${prefix}/plugins.xml" />

</export>


<!-- These are really "soft" dependencies, and are just required if you need them for launch... -->
<!-- <depend condition="$ROS_VERSION == 1">ov_eval</depend>-->
<!-- <depend condition="$ROS_VERSION == 1">ov_data</depend>-->
Expand Down
5 changes: 5 additions & 0 deletions ov_msckf/plugins.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<library path="lib/libRunSubscribeMsckf">
<class name="run_subscribe_msckf/RunSubscribeMsckf" type="run_subscribe_msckf::RunSubscribeMsckf" base_class_type="nodelet::Nodelet">
<description>RunSubscribeMsckf nodelet</description>
</class>
</library>
103 changes: 45 additions & 58 deletions ov_msckf/src/run_subscribe_msckf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,54 +25,49 @@
#include "core/VioManagerOptions.h"
#include "utils/dataset_reader.h"

#if ROS_AVAILABLE == 1
#include "ros/ROS1Visualizer.h"
#include <ros/ros.h>
#elif ROS_AVAILABLE == 2
#include "ros/ROS2Visualizer.h"
#include <rclcpp/rclcpp.hpp>
#endif
#include <nodelet/nodelet.h>

using namespace ov_msckf;

std::shared_ptr<VioManager> sys;
#if ROS_AVAILABLE == 1
std::shared_ptr<ROS1Visualizer> viz;
#elif ROS_AVAILABLE == 2
std::shared_ptr<ROS2Visualizer> viz;
#endif
namespace run_subscribe_msckf {

// Main function
int main(int argc, char **argv) {
class RunSubscribeMsckf : public nodelet::Nodelet {

public:
virtual void onInit();

private:
std::shared_ptr<VioManager> sys;
std::shared_ptr<ROS1Visualizer> viz;
std::shared_ptr<ros::NodeHandle> nh_ptr;
};

/* main //{ */

void RunSubscribeMsckf::onInit() {

// Ensure we have a path, if the user passes it then we should use it
std::string config_path = "unset_path_to_config.yaml";
if (argc > 1) {
config_path = argv[1];
}
/* if (argc > 1) { */
/* config_path = argv[1]; */
/* } */

/* // Launch our ros node */
/* ros::init(argc, argv, "run_subscribe_msckf"); */

ros::NodeHandle nh = nodelet::Nodelet::getMTPrivateNodeHandle();
ros::Time::waitForValid();

#if ROS_AVAILABLE == 1
// Launch our ros node
ros::init(argc, argv, "run_subscribe_msckf");
auto nh = std::make_shared<ros::NodeHandle>("~");
nh->param<std::string>("config_path", config_path, config_path);
#elif ROS_AVAILABLE == 2
// Launch our ros node
rclcpp::init(argc, argv);
rclcpp::NodeOptions options;
options.allow_undeclared_parameters(true);
options.automatically_declare_parameters_from_overrides(true);
auto node = std::make_shared<rclcpp::Node>("run_subscribe_msckf", options);
node->get_parameter<std::string>("config_path", config_path);
#endif
nh.param<std::string>("config_path", config_path, config_path);

// Load the config
auto parser = std::make_shared<ov_core::YamlParser>(config_path);
#if ROS_AVAILABLE == 1
parser->set_node_handler(nh);
#elif ROS_AVAILABLE == 2
parser->set_node(node);
#endif


nh_ptr = std::make_shared<ros::NodeHandle>(nh);
parser->set_node_handler(nh_ptr);

// Verbosity
std::string verbosity = "DEBUG";
Expand All @@ -84,13 +79,8 @@ int main(int argc, char **argv) {
params.print_and_load(parser);
params.use_multi_threading_subs = true;
sys = std::make_shared<VioManager>(params);
#if ROS_AVAILABLE == 1
viz = std::make_shared<ROS1Visualizer>(nh, sys);
viz->setup_subscribers(parser);
#elif ROS_AVAILABLE == 2
viz = std::make_shared<ROS2Visualizer>(node, sys);
viz = std::make_shared<ROS1Visualizer>(nh_ptr, sys);
viz->setup_subscribers(parser);
#endif

// Ensure we read in all parameters required
if (!parser->successful()) {
Expand All @@ -100,26 +90,23 @@ int main(int argc, char **argv) {

// Spin off to ROS
PRINT_DEBUG("done...spinning to ros\n");
#if ROS_AVAILABLE == 1
// ros::spin();
ros::AsyncSpinner spinner(0);
spinner.start();
ros::waitForShutdown();
#elif ROS_AVAILABLE == 2
// rclcpp::spin(node);
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
#endif
/* ros::AsyncSpinner spinner(0); */
/* spinner.start(); */
/* ros::waitForShutdown(); */

// Final visualization
viz->visualize_final();
#if ROS_AVAILABLE == 1
ros::shutdown();
#elif ROS_AVAILABLE == 2
rclcpp::shutdown();
#endif
/* viz->visualize_final(); */
/* ros::shutdown(); */

// Done!
return EXIT_SUCCESS;
/* return EXIT_SUCCESS; */
}

//}

} // namespace run_subscribe_msckf

/* every nodelet must include macros which export the class as a nodelet plugin */
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(run_subscribe_msckf::RunSubscribeMsckf, nodelet::Nodelet);
125 changes: 125 additions & 0 deletions ov_msckf/src/run_subscribe_msckf_back.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
/*
* OpenVINS: An Open Platform for Visual-Inertial Research
* Copyright (C) 2018-2023 Patrick Geneva
* Copyright (C) 2018-2023 Guoquan Huang
* Copyright (C) 2018-2023 OpenVINS Contributors
* Copyright (C) 2018-2019 Kevin Eckenhoff
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

#include <memory>

#include "core/VioManager.h"
#include "core/VioManagerOptions.h"
#include "utils/dataset_reader.h"

#if ROS_AVAILABLE == 1
#include "ros/ROS1Visualizer.h"
#include <ros/ros.h>
#elif ROS_AVAILABLE == 2
#include "ros/ROS2Visualizer.h"
#include <rclcpp/rclcpp.hpp>
#endif

using namespace ov_msckf;

std::shared_ptr<VioManager> sys;
#if ROS_AVAILABLE == 1
std::shared_ptr<ROS1Visualizer> viz;
#elif ROS_AVAILABLE == 2
std::shared_ptr<ROS2Visualizer> viz;
#endif

// Main function
int main(int argc, char **argv) {

// Ensure we have a path, if the user passes it then we should use it
std::string config_path = "unset_path_to_config.yaml";
if (argc > 1) {
config_path = argv[1];
}

#if ROS_AVAILABLE == 1
// Launch our ros node
ros::init(argc, argv, "run_subscribe_msckf");
auto nh = std::make_shared<ros::NodeHandle>("~");
nh->param<std::string>("config_path", config_path, config_path);
#elif ROS_AVAILABLE == 2
// Launch our ros node
rclcpp::init(argc, argv);
rclcpp::NodeOptions options;
options.allow_undeclared_parameters(true);
options.automatically_declare_parameters_from_overrides(true);
auto node = std::make_shared<rclcpp::Node>("run_subscribe_msckf", options);
node->get_parameter<std::string>("config_path", config_path);
#endif

// Load the config
auto parser = std::make_shared<ov_core::YamlParser>(config_path);
#if ROS_AVAILABLE == 1
parser->set_node_handler(nh);
#elif ROS_AVAILABLE == 2
parser->set_node(node);
#endif

// Verbosity
std::string verbosity = "DEBUG";
parser->parse_config("verbosity", verbosity);
ov_core::Printer::setPrintLevel(verbosity);

// Create our VIO system
VioManagerOptions params;
params.print_and_load(parser);
params.use_multi_threading_subs = true;
sys = std::make_shared<VioManager>(params);
#if ROS_AVAILABLE == 1
viz = std::make_shared<ROS1Visualizer>(nh, sys);
viz->setup_subscribers(parser);
#elif ROS_AVAILABLE == 2
viz = std::make_shared<ROS2Visualizer>(node, sys);
viz->setup_subscribers(parser);
#endif

// Ensure we read in all parameters required
if (!parser->successful()) {
PRINT_ERROR(RED "unable to parse all parameters, please fix\n" RESET);
std::exit(EXIT_FAILURE);
}

// Spin off to ROS
PRINT_DEBUG("done...spinning to ros\n");
#if ROS_AVAILABLE == 1
// ros::spin();
ros::AsyncSpinner spinner(0);
spinner.start();
ros::waitForShutdown();
#elif ROS_AVAILABLE == 2
// rclcpp::spin(node);
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
#endif

// Final visualization
viz->visualize_final();
#if ROS_AVAILABLE == 1
ros::shutdown();
#elif ROS_AVAILABLE == 2
rclcpp::shutdown();
#endif

// Done!
return EXIT_SUCCESS;
}

0 comments on commit 8f10396

Please sign in to comment.