一、基础配置
- 在rosworksapce中建立gui模版项目,在src目录下
catkin_create_qt_pkg test 创建一个包名为test的ros_gui模板 - 添加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
在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();
}