Merge branch 'master' into gehongbo_branch

test
13195980010 3 years ago
commit 755b094675

@ -124,12 +124,12 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON)
set(SOURCES
src/include/qnode.hpp
src/include/joystick.h
src/include/dashboard.h
src/main/main.cpp
src/main/mainwindow.cpp
src/main/qnode.cpp
src/main/joystick.cpp
src/main/dashboard.cpp
src/ui/mainwindow.hpp
src/ui/mainwindow.ui

@ -0,0 +1,53 @@
#ifndef DASHBOARD_H
#define DASHBOARD_H
#include <QWidget>
class DashBoard : public QWidget {
Q_OBJECT
public:
enum Gear {
kGear_1 = 1,
kGear_2,
kGear_3,
kGear_4,
kGear_5,
kGear_6,
kGear_7,
kGear_8,
kGear_D,
kGear_N,
kGear_P,
kGear_R
};
public:
explicit DashBoard(QWidget* parent = nullptr);
public slots:
void set_gear(const Gear gear);
void set_rpm(const int rpm);
void set_speed(const int speed);
void set_temperature(const double temperature);
void set_oil(const int oil);
protected:
void paintEvent(QPaintEvent* event);
private:
void draw_tachometer(QPainter& painter); // 转速表
void draw_speedometer(QPainter& painter); // 迈速表
void draw_gear(QPainter& painter); // 挡位
void draw_thermometer(QPainter& painter); // 水箱温度计
void draw_oil_meter(QPainter& painter); // 油表
private:
Gear _gear{kGear_N};
int _rpm;
int _speed;
double _temperature;
int _oil;
QWidget* parent;
};
#endif // DASHBOARD_H

@ -7,6 +7,9 @@
#include <iostream>
#include <QImage>
#include <QThread>
#include <QStringListModel>
#include <QSettings>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
@ -17,7 +20,9 @@
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <geometry_msgs/Twist.h>
#include <QThread>
#include <nav_msgs/Odometry.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Float32.h>
using namespace std;
@ -31,13 +36,27 @@ public:
void SubAndPubTopic();
void KeyboardMove(char key, float speed_linear, float speed_trun);
Q_SIGNALS:
void speed_x(double x);
void speed_th(double th);
void power(float p);
private:
int init_argc;
char **init_argv;
ros::Subscriber cmdVel_sub;
ros::Publisher chatter_publisher;
ros::Subscriber chatter_subscriber;
ros::Publisher cmd_pub;
ros::Subscriber cmdVel_sub;
ros::Subscriber power_sub;
QString odom_topic;
QString batteryState_topic;
void speedCallback(const nav_msgs::Odometry::ConstPtr& msg);
void powerCallback(const std_msgs::Float32& message_holder);
void myCallback(const std_msgs::Float64& message_holder);
};

@ -0,0 +1,384 @@
#include "../include/dashboard.h"
#include <qapplication.h>
#include <qpainter.h>
#include <qpainterpath.h>
#include <QtGui/QFontDatabase>
#include "QDebug"
DashBoard::DashBoard(QWidget* parent)
: QWidget(parent),
_gear(kGear_1),
_rpm(0),
_speed(0),
_temperature(0),
_oil(0) {
QFontDatabase::addApplicationFont(":/fonts/DejaVuSans.ttf");
this->resize(parent->size());
this->parent = parent;
}
void DashBoard::set_gear(const DashBoard::Gear gear) {
_gear = gear;
update();
}
void DashBoard::set_rpm(const int rpm) {
_rpm = rpm;
update();
}
void DashBoard::set_speed(const int speed) {
_speed = speed;
_rpm = speed;
update();
}
void DashBoard::set_temperature(const double temperature) {
_temperature = temperature;
update();
}
void DashBoard::set_oil(const int oil) {
_oil = oil;
update();
}
void DashBoard::paintEvent(QPaintEvent* event) {
this->resize(parent->size());
QWidget::paintEvent(event);
int side = qMin(int(parent->width() / 1.8), parent->height());
QPainter painter(this);
painter.setRenderHint(QPainter::Antialiasing);
painter.translate(parent->width() / 2, parent->height() / 2);
painter.scale(side / 200.0, side / 200.0);
painter.setPen(Qt::NoPen);
painter.setBrush(Qt::NoBrush);
draw_tachometer(painter);
draw_speedometer(painter);
draw_gear(painter);
draw_thermometer(painter);
draw_oil_meter(painter);
}
void DashBoard::draw_tachometer(QPainter& painter) {
static QColor normal_color(26, 245, 245, 245);
static QColor overrun_color(245, 64, 64, 225);
// 绘制表盘外檐
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
QRect rect(-95, -95, 190, 190);
painter.drawArc(rect, 0, 270 * 16);
painter.restore();
// 绘制红色区域
painter.save();
static QRectF rectangle_outer(-95, -95, 190, 190);
static QRectF rectangle_inner(-87, -87, 174, 174);
painter.setBrush(overrun_color);
QPainterPath path;
path.arcTo(rectangle_outer, 0.0, 108.0);
path.arcTo(rectangle_inner, 108, -108);
painter.drawPath(path);
painter.restore();
// 绘制大刻度
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
painter.rotate(90);
for (int i = 0; i < 21; ++i) {
painter.drawLine(88, 0, 94, 0);
painter.rotate(13.5);
}
painter.restore();
// 绘制小刻度
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
painter.rotate(90);
for (int i = 0; i < 100; ++i) {
painter.drawLine(91, 0, 94, 0);
painter.rotate(2.7);
}
painter.restore();
// 绘制表盘数字
painter.save();
painter.rotate(90);
painter.setPen(normal_color);
painter.setFont(QFont("Times", 14));
for (int i = 0; i < 11; ++i) {
painter.save();
if (i > 6) {
painter.setPen(overrun_color);
}
painter.rotate(27.0 * i);
painter.translate(76, 0);
painter.rotate(270 - 27.0 * i);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(i));
painter.restore();
}
painter.restore();
// 绘制指针
static const QPoint hand[] = {QPoint(-4, 0), QPoint(0, 94), QPoint(4, 0),
QPoint(0, -6)};
static QColor hand_color(26, 245, 245, 176);
painter.save();
painter.setPen(Qt::NoPen);
painter.setBrush(hand_color);
painter.rotate(27.0 * (_rpm / 10.0));
painter.drawConvexPolygon(hand, 4);
painter.restore();
// 绘制文字
painter.save();
painter.setPen(normal_color);
painter.setFont(QFont("DejaVu Sans", 8));
painter.drawText(QRect(-50, -70, 100, 50), Qt::AlignCenter, "×10");
painter.setFont(QFont("DejaVu Sans", 8, 50, true));
painter.drawText(QRect(-50, 34, 32, 16), Qt::AlignCenter, "CM/S");
painter.restore();
}
void DashBoard::draw_speedometer(QPainter& painter) {
painter.save();
painter.setPen(QColor(64, 64, 245));
painter.setFont(QFont("DejaVu Sans", 6, 50, true));
painter.drawText(QRect(80, 50, 70, 20), Qt::AlignCenter, "SPEED");
painter.setPen(QColor(26, 245, 245));
painter.setFont(QFont("DejaVu Sans", 24, 63, true));
painter.drawText(QRect(80, 50, 70, 50), Qt::AlignBottom | Qt::AlignLeft,
QString("%0").arg(QString::number(_speed), 3, '0'));
painter.setPen(QColor(26, 245, 245));
painter.setFont(QFont("DejaVu Sans", 8, 63, true));
painter.drawText(QRect(145, 75, 40, 20), Qt::AlignBottom | Qt::AlignLeft,
"cm/s");
painter.restore();
}
void DashBoard::draw_gear(QPainter& painter) {
static QRect gear_rect(0, 0, 80, 80);
static QRect suffix_rect(48, 48, 32, 32);
static QFont suffix_font("DejaVu Sans", 16, 63, true);
painter.save();
painter.setPen(QPen(QColor(26, 245, 245), 1, Qt::SolidLine));
painter.setFont(QFont("DejaVu Sans", 48, 63, true));
switch (_gear) {
case kGear_1:
painter.drawText(gear_rect, Qt::AlignCenter, QString::number(_gear));
painter.setFont(suffix_font);
painter.drawText(suffix_rect, Qt::AlignCenter, "st");
break;
case kGear_2:
painter.drawText(gear_rect, Qt::AlignCenter, QString::number(_gear));
painter.setFont(suffix_font);
painter.drawText(suffix_rect, Qt::AlignCenter, "nd");
break;
case kGear_3:
painter.drawText(gear_rect, Qt::AlignCenter, QString::number(_gear));
painter.setFont(suffix_font);
painter.drawText(suffix_rect, Qt::AlignCenter, "rd");
break;
case kGear_4:
case kGear_5:
case kGear_6:
case kGear_7:
case kGear_8:
painter.drawText(gear_rect, Qt::AlignCenter, QString::number(_gear));
painter.setFont(suffix_font);
painter.drawText(suffix_rect, Qt::AlignCenter, "th");
break;
case kGear_D:
painter.drawText(gear_rect, Qt::AlignCenter, "D");
break;
case kGear_N:
painter.drawText(gear_rect, Qt::AlignCenter, "N");
break;
case kGear_P:
painter.drawText(gear_rect, Qt::AlignCenter, "P");
break;
case kGear_R:
painter.drawText(gear_rect, Qt::AlignCenter, "R");
break;
default:
break;
}
painter.restore();
}
void DashBoard::draw_thermometer(QPainter& painter) {
painter.save();
painter.drawImage(QRect(115, -60, 8, 16),
QImage("://images/temperature-icon.png"));
painter.translate(-160, 100);
static QColor normal_color(26, 245, 245, 245);
static QColor overrun_color(245, 64, 64, 225);
// 绘制表盘外檐
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
QRect rect(-300, -300, 600, 600);
painter.drawArc(rect, 12 * 16, 20 * 16);
painter.restore();
// 绘制刻度
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
painter.rotate(-12);
painter.drawLine(300, 0, 306, 0);
painter.rotate(-10);
painter.drawLine(300, 0, 304, 0);
painter.rotate(-10);
painter.drawLine(300, 0, 306, 0);
painter.restore();
// 绘制刻度值
painter.save();
painter.setPen(normal_color);
painter.setFont(QFont("DejaVu Sans", 6));
painter.rotate(-12);
painter.save();
painter.translate(316, 0);
painter.rotate(12);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(0) + "°C");
painter.restore();
painter.rotate(-10);
painter.save();
painter.translate(317, 0);
painter.rotate(22);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(50) + "°C");
painter.restore();
painter.rotate(-10);
painter.save();
painter.translate(320, 0);
painter.rotate(32);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(100) + "°C");
painter.restore();
painter.restore();
// 绘制红色区域
painter.save();
static QRectF rectangle_outer(-304, -304, 608, 608);
static QRectF rectangle_inner(-300.5, -300.5, 601, 601);
painter.setBrush(overrun_color);
QPainterPath path;
path.arcTo(rectangle_outer, 28, 3.9);
path.arcTo(rectangle_inner, 31.9, -3.9);
painter.drawPath(path);
painter.restore();
// 绘制指针
painter.save();
painter.setPen(QPen(overrun_color, 1, Qt::SolidLine));
painter.rotate(-12 - 0.2 * _temperature);
painter.drawLine(298, 0, 306, 0);
painter.restore();
painter.restore();
}
void DashBoard::draw_oil_meter(QPainter& painter) {
painter.save();
painter.drawImage(QRect(-130, -60, 16, 16),
QImage("://images/fuel-icon.png"));
painter.translate(160, 100);
painter.rotate(180);
static QColor normal_color(26, 245, 245, 245);
static QColor overrun_color(245, 64, 64, 225);
// 绘制表盘外檐
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
QRect rect(-300, -300, 600, 600);
painter.drawArc(rect, -12 * 16, -20 * 16);
painter.restore();
// 绘制刻度
painter.save();
painter.setPen(QPen(normal_color, 1, Qt::SolidLine));
painter.rotate(12);
painter.drawLine(300, 0, 306, 0);
painter.rotate(10);
painter.drawLine(300, 0, 304, 0);
painter.rotate(10);
painter.drawLine(300, 0, 306, 0);
painter.restore();
// 绘制刻度值
painter.save();
painter.setPen(normal_color);
painter.setFont(QFont("DejaVu Sans", 6));
painter.rotate(12);
painter.save();
painter.translate(316, 0);
painter.rotate(168);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(0) + "%");
painter.restore();
painter.rotate(10);
painter.save();
painter.translate(317, 0);
painter.rotate(158);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(50) + "%");
painter.restore();
painter.rotate(10);
painter.save();
painter.translate(320, 0);
painter.rotate(148);
painter.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter,
QString::number(100) + "%");
painter.restore();
painter.restore();
// 绘制红色区域
painter.save();
static QRectF rectangle_outer(-304, -304, 608, 608);
static QRectF rectangle_inner(-300.5, -300.5, 601, 601);
painter.setBrush(overrun_color);
QPainterPath path;
path.arcTo(rectangle_outer, -12.1, -3.9);
path.arcTo(rectangle_inner, -16, 3.9);
painter.drawPath(path);
painter.restore();
// 绘制指针
painter.save();
painter.setPen(QPen(overrun_color, 1, Qt::SolidLine));
painter.rotate(12 + 0.2 * _oil);
painter.drawLine(298, 0, 306, 0);
painter.restore();
painter.restore();
}

@ -18,7 +18,10 @@ QNode::~QNode() {
}
bool QNode::init() {
QSettings topic_setting("ros_controller", "settings");
odom_topic = topic_setting.value("topic/topic_odom", "odom").toString();
batteryState_topic =
topic_setting.value("topic/topic_power", "battery_state").toString();
ros::init(init_argc,init_argv,"Air_Ground_CEC",
ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
SubAndPubTopic();
@ -27,6 +30,11 @@ bool QNode::init() {
void QNode::SubAndPubTopic(){
ros::NodeHandle n;
//创建速度话题的订阅者
cmdVel_sub = n.subscribe<nav_msgs::Odometry>(odom_topic.toStdString(), 200,
&QNode::speedCallback, this);
//power_sub = n.subscribe(batteryState_topic.toStdString(), 1000,
// &QNode::powerCallback, this);
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
}
@ -62,3 +70,9 @@ void QNode::KeyboardMove(char key, float speed_linear, float speed_trun){
ros::spinOnce();
}
//速度回调函数
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
{
emit speed_x(msg->twist.twist.linear.x);
emit speed_th(msg->twist.twist.angular.z);
}

@ -8,6 +8,7 @@
#include "ui_mainwindow.h"
#include "../include/joystick.h"
#include "../include/qnode.hpp"
#include "../include/dashboard.h"
namespace Ui {
class MainWindow;
@ -38,6 +39,8 @@ public slots:
void slot_keyboard_control();
//void slot_command_control(int linear, int angular);
void slot_rockKeyChange(int);
void slot_speed_x(double x);
void slot_speed_th(double th);
void Slider_raw_valueChanged(int v);
void Slider_linear_valueChanged(int v);
@ -47,6 +50,8 @@ private:
Ui::MainWindow *ui;
QNode qnode;
JoyStick *rock_widget;
DashBoard *m_DashBoard_x;
DashBoard *m_DashBoard_th;
void initUis();
void setBtnStyles();

Loading…
Cancel
Save