在QT中開發librviz顯示雷達點雲數據

一、基礎配置

  1. 在rosworksapce中建立gui模版項目,在src目錄下
    catkin_create_qt_pkg test 創建一個包名爲test的ros_gui模板
  2. 添加rviz包依賴
    在CMakeLists.txt中添加
    find_package(catkin REQUIRED COMPONENTS rviz roscpp)
    在package.xml中添加
<build_depend>roscpp</build_depend>
  <run_depend>roscpp</run_depend>
  <build_depend>rospy</build_depend>
  <run_depend>rospy</run_depend>
  <build_depend>rviz</build_depend>
  <run_depend>rviz</run_depend>

二、UI

ui
在main_window.ui中在centralwidget下添加verticalLayout,verticalLayout就是我要在上邊添加rviz的佈局,而這個close的button是爲了關閉當前頁面,並且結束終端的一些操作。

三、創建rviz相關的class

3.1引入:

#include <rviz/visualization_manager.h>

#include <rviz/render_panel.h>

#include <rviz/display.h>

#include <rviz/default_plugin/view_controllers/orbit_view_controller.h>

#include <rviz/view_manager.h>

3.2 在main_window.hpp中定義一個class,就是顯示rviz的組件

class RvizPlugin: public QObject{

    Q_OBJECT

public:

    RvizPlugin(QVBoxLayout* ui){

//創建rviz的容器,並將該容器作爲組建加入到ui內,其中關鍵class爲VisualizationManager,是個管理類,起到控制創建rviz圖層和設置座標系的作用。

      render_panel_=new rviz::RenderPanel;

       ui->addWidget(render_panel_);

       manager_=new rviz::VisualizationManager(render_panel_);

      render_panel_->initialize(manager_->getSceneManager(),manager_);

       manager_->initialize();

       manager_->startUpdate();

      manager_->setFixedFrame("/world”);

//創建一個類型爲rviz/PointCloud2的圖層,用於接收topic爲points_map的點雲數據,就是我最終底圖的圖層

      rviz::Display *map_=manager_->createDisplay("rviz/PointCloud2","pointCloud2",true);

      ROS_ASSERT(map_!=NULL);

      map_->subProp("Topic")->setValue("/points_map");

      map_->subProp("Invert Rainbow")->setValue("true");

      map_->subProp("Style")->setValue("Points");

      map_->subProp("Size (Pixels)")->setValue("2");

      //map_->subProp("Decay Time")->setValue("0");

      map_->subProp("Color Transformer")->setValue("FlatColor");

      map_->subProp("Queue Size")->setValue("10");

      map_->subProp("Alpha")->setValue("0.05");

//創建一個類型爲rviz/PointCloud2的圖層,用於接收topic爲points_raw的點雲數據,就是雷達實時掃描數據的展示

      rviz::Display *robot_=manager_->createDisplay("rviz/PointCloud2","pointCloud2",true);

       ROS_ASSERT(robot_!=NULL);

       robot_->subProp("Topic")->setValue("/points_raw");

       //robot_->subProp("Use Rainbow")->setValue(true);

       robot_->subProp("Size (Pixels)")->setValue("2");

       robot_->subProp("Style")->setValue("Points");

       //robot_->subProp("Autocompute Intensity Bounds")->setValue(true);

       //robot_->subProp("Color Transformer")->setValue("Intensity");

       robot_->subProp("Queue Size")->setValue("10");

       robot_->subProp("Alpha")->setValue("0.3");

       //robot_->subProp("Channel Name")->setValue("Intensity");

  //     robot_->subProp("Color Transformer")->setValue("Intensity");

  //     robot_->subProp("Color Transformer")->setValue("Intensity");

//這個是創建小車模型的圖層,由urdf文件控制

       rviz::Display *car=manager_->createDisplay("rviz/RobotModel","adjustable robot",true);

            ROS_ASSERT(car!=NULL);

           car->subProp("Robot Description")->setValue("robot_description");

      manager_->startUpdate();

//設置整個地圖的展示方式,如視角、距離、偏航等

      viewManager = manager_->getViewManager();

      viewManager->setRenderPanel(render_panel_);

      viewManager->setCurrentViewControllerType("rviz/ThirdPersonFollower");

      viewManager->getCurrent()->subProp("Target Frame")->setValue("/base_link");

      viewManager->getCurrent()->subProp("Near Clip Distance")->setValue("0.01");

      viewManager->getCurrent()->subProp("Focal Point")->setValue("1.90735e-06;-7.62939e-06;0");

      viewManager->getCurrent()->subProp("Focal Shape Size")->setValue("0.05");

      viewManager->getCurrent()->subProp("Focal Shape Fixed Size")->setValue("true");

      //juli

      viewManager->getCurrent()->subProp("Distance")->setValue("204.168");

      //chetou jiaodu

      viewManager->getCurrent()->subProp("Yaw")->setValue("1.7004");

      //fujiao

      viewManager->getCurrent()->subProp("Pitch")->setValue("0.770398");

    }

public slots:

private:

    rviz::RenderPanel* render_panel_;// = new rviz::RenderPanel;

    rviz::VisualizationManager *manager_;// =  new rviz::VisualizationManager(pointCloud_panel);

    rviz::ViewManager* viewManager;

};

3.3 在.cpp文件中直接使用即可

RvizPlugin rvi(this->ui.verticalLayout);

3.4 close按鈕的關閉操作

void rtourMap::MainWindow::on_close_clicked()
{
    system("killall -9 rosbag");
    this->close();
}

四、效果展示

pointCloud

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章