Hello,
I created a plugin panel in rviz. See below I want to call rtabmap_ros function from the button of plug-in panel. What kind of method is good? Maybe I think that it is necessary to call the function equivalent to "rosservice call / rtabmap / pause" if it is pause function. **plugin panel in rviz source using namespace std; RvizPanel :: RvizPanel (QWidget * parent) : rviz :: Panel (parent) { QVBoxLayout * layout = new QVBoxLayout; btn_pause = new QPushButton ("Pause / Resume"); layout-> addWidget (btn_pause); this-> setLayout (layout); connect (btn_pause, SIGNAL (clicked ()), this, SLOT (btn_pause_clicked ())); } void RvizPanel :: btn_pause_clicked () { //I want to put a function that calls rtabmap_ros here. } } #include <pluginlib / class_list_macros.h> PLUGINLIB_EXPORT_CLASS (rviz_plugin :: RvizPanel, rviz :: Panel) ** Thank you, koba |
Administrator
|
Hi,
#include <std_srvs/Empty.h> // Pause rtabmap if(!ros::service::call("/rtabmap/pause", emptySrv)) { ROS_ERROR("Cannot call \"/rtabmap/pause\" service"); } // Resume rtabmap if(!ros::service::call("/rtabmap/resume", emptySrv)) { ROS_ERROR("Can't call \"/rtabmap/resume\" service"); } // To know if rtabmap is paused bool paused = false; ros::NodeHandle nh; nh.getParam("/rtabmap/is_rtabmap_paused", paused);Here we assume that rtabmap is launched in "rtabmap" namespace. cheers, Mathieu |
Hi,
Thank you for your answer. It worked well. Thank you very much for your help. I want to create a ply file using rtabmap_ros. In that case, how should I call rtabmap_ros? In the rtabmap procedure, select Detection-Pause and use File-Export3D clouds (* .ply * pcd * .obj) ... to output. Many Thanks, koba |
Administrator
|
Hi,
You can use pcl_ros to save point clouds to PCD file, then use pcl tools to convert to file in format you want: $ rosrun pcl_ros pointcloud_to_pcd input:=/rtabmap/cloud_map $ pcl_pcd2ply input.pcd output.ply If you want to regenerate the cloud in different density, there is no easy workaround out of "File->Export 3D clouds..." of rtabmapviz. There is a simple c++ example here on how to export the point cloud from a database file to PLY, but there are not as many options than with the UI approach. $ ~/rtabmap/bin/rtabmap-export rtabmap.db cheers, Mathieu |
Hi,
Thank you for your answer. I tried to put the process in reference to the sent answer. I want to generate a ply file at that point when I press the STOP button that I incorporated as an RVIZ plug-in. I tried to output cloud.ply by calling the following command when I pressed the STOP button. ~ / rtabmap / bin / rtabmap-export rtabmap.dbAt that time, the following error was displayed on multiple lines. [ERROR] (2019-06-12 14: 28: 22.372) VWDictionary.cpp: 672 :: addWordRef () Not found word 8810 (dict size = 0) [ERROR] (2019-06-12 14: 28: 22.372) VWDictionary.cpp: 672 :: addWordRef () Not found word 8811 (dict size = 0)Probably, it is because rtabmap.db is not saved as a final form unless rtabmap_ros ends. In such a case, what kind of correspondence method can be considered? In another method, I executed the following command on another terminal. Then the pcd file was output each time the point cloud data was updated. In this case, is it the process to convert to ply for the newest pcd file (input.pcd) when the STOP button is pressed? $ rosrun pcl_ros pointcloud_to_pcd input: = / rtabmap / cloud_map $ pcl_pcd2ply input.pcd output.plyMany thank you, koba |
Administrator
|
Yes, rtabmap.db should be closed before accessing it with other application. Online, the best approach is to save cloud_map like you did. Otherwise, when clicking on stop, you could kill rtabmap node so that it closes safely the database, then use rtabmap-export tool. However, restarting rtabmap node may not be obvious. Other approach is to call /rtabmap/backup service. It will create rtabmap.db.back in ~/.ros folder that could be used to export the cloud with rtabmap-export.
cheers, Mathieu |
Free forum by Nabble | Edit this page |