.. _program_listing_file__tmp_ws_src_rtabmap_ros_include_rtabmap_ros_GuiWrapper.h: Program Listing for File GuiWrapper.h ===================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rtabmap_ros/include/rtabmap_ros/GuiWrapper.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the Universite de Sherbrooke nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #ifndef GUIWRAPPER_H_ #define GUIWRAPPER_H_ #include #include #include #include "rtabmap_ros/msg/info.hpp" #include "rtabmap_ros/msg/map_data.hpp" #include "rtabmap_ros/msg/odom_info.hpp" #include "rtabmap_ros/msg/goal.hpp" #include "rtabmap/utilite/UEventsHandler.h" #include "rtabmap/core/Transform.h" #include #include #include #include #include #include #include "rtabmap_ros/srv/get_map.hpp" #include namespace rtabmap { class MainWindow; class PreferencesDialog; } class QApplication; namespace rtabmap_ros { class GuiWrapper : public rclcpp::Node, public UEventsHandler, public CommonDataSubscriber { public: RTABMAP_ROS_PUBLIC explicit GuiWrapper(const rclcpp::NodeOptions & options); virtual ~GuiWrapper(); protected: virtual bool handleEvent(UEvent * anEvent); private: void infoMapCallback(const rtabmap_ros::msg::Info::ConstSharedPtr infoMsg, const rtabmap_ros::msg::MapData::ConstSharedPtr mapMsg); void goalPathCallback(const rtabmap_ros::msg::Goal::ConstSharedPtr goalMsg, const nav_msgs::msg::Path::ConstSharedPtr pathMsg); void goalReachedCallback(const std_msgs::msg::Bool::ConstSharedPtr value); virtual void commonMultiCameraCallback( const nav_msgs::msg::Odometry::ConstSharedPtr & odomMsg, const rtabmap_ros::msg::UserData::ConstSharedPtr & userDataMsg, const std::vector & imageMsgs, const std::vector & depthMsgs, const std::vector & cameraInfoMsgs, const std::vector & depthCameraInfoMsgs, const sensor_msgs::msg::LaserScan & scanMsg, const sensor_msgs::msg::PointCloud2 & scan3dMsg, const rtabmap_ros::msg::OdomInfo::ConstSharedPtr& odomInfoMsg, const std::vector & globalDescriptorMsgs = std::vector(), const std::vector > & localKeyPoints = std::vector >(), const std::vector > & localPoints3d = std::vector >(), const std::vector & localDescriptors = std::vector()); virtual void commonStereoCallback( const nav_msgs::msg::Odometry::ConstSharedPtr & odomMsg, const rtabmap_ros::msg::UserData::ConstSharedPtr & userDataMsg, const cv_bridge::CvImageConstPtr& leftImageMsg, const cv_bridge::CvImageConstPtr& rightImageMsg, const sensor_msgs::msg::CameraInfo& leftCamInfoMsg, const sensor_msgs::msg::CameraInfo& rightCamInfoMsg, const sensor_msgs::msg::LaserScan & scan2dMsg, const sensor_msgs::msg::PointCloud2 & scan3dMsg, const rtabmap_ros::msg::OdomInfo::ConstSharedPtr& odomInfoMsg, const std::vector & globalDescriptorMsgs = std::vector(), const std::vector & localKeyPoints = std::vector(), const std::vector & localPoints3d = std::vector(), const cv::Mat & localDescriptors = cv::Mat()); virtual void commonLaserScanCallback( const nav_msgs::msg::Odometry::ConstSharedPtr & odomMsg, const rtabmap_ros::msg::UserData::ConstSharedPtr & userDataMsg, const sensor_msgs::msg::LaserScan & scan2dMsg, const sensor_msgs::msg::PointCloud2 & scan3dMsg, const rtabmap_ros::msg::OdomInfo::ConstSharedPtr& odomInfoMsg, const rtabmap_ros::msg::GlobalDescriptor & globalDescriptor = rtabmap_ros::msg::GlobalDescriptor()); virtual void commonOdomCallback( const nav_msgs::msg::Odometry::ConstSharedPtr & odomMsg, const rtabmap_ros::msg::UserData::ConstSharedPtr & userDataMsg, const rtabmap_ros::msg::OdomInfo::ConstSharedPtr& odomInfoMsg); void defaultCallback(const nav_msgs::msg::Odometry::SharedPtr & odomMsg); void processRequestedMap(const rtabmap_ros::msg::MapData & map); bool callEmptyService(const std::string & name); bool callMapDataService(const std::string & name, bool global, bool optimized, bool graphOnly); private: rtabmap::PreferencesDialog * prefDialog_; rtabmap::MainWindow * mainWindow_; std::string cameraNodeName_; double lastOdomInfoUpdateTime_; std::string rtabmapNodeName_; // odometry subscription stuffs std::string frameId_; std::string odomFrameId_; double waitForTransform_; bool odomSensorSync_; double maxOdomUpdateRate_; std::shared_ptr tfBuffer_; std::shared_ptr tfListener_; rclcpp::Publisher::SharedPtr republishNodeDataPub_; message_filters::Subscriber infoTopic_; message_filters::Subscriber mapDataTopic_; message_filters::Subscriber goalTopic_; message_filters::Subscriber pathTopic_; rclcpp::Subscription::SharedPtr goalReachedTopic_; typedef message_filters::sync_policies::ExactTime< rtabmap_ros::msg::Info, rtabmap_ros::msg::MapData> MyInfoMapSyncPolicy; message_filters::Synchronizer * infoMapSync_; typedef message_filters::sync_policies::ExactTime< rtabmap_ros::msg::Goal, nav_msgs::msg::Path> MyGoalPathSyncPolicy; message_filters::Synchronizer * goalPathSync_; }; } #endif /* GUIWRAPPER_H_ */