mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-02 21:24:12 +05:30
66 lines
1.4 KiB
C++
66 lines
1.4 KiB
C++
#ifndef SPELLER
|
|
#define SPELLER
|
|
|
|
#include "QLabel"
|
|
#include "ble_connect/ble_connect.h"
|
|
#include "mapview/mapview.h"
|
|
#include <QKeyEvent>
|
|
#include <QThread>
|
|
#include <geometry_msgs/Point.h>
|
|
#include <geometry_msgs/Pose.h>
|
|
#include <geometry_msgs/PoseStamped.h>
|
|
#include <geometry_msgs/Quaternion.h>
|
|
#include <map>
|
|
#include <nav_msgs/GetMap.h>
|
|
#include <nav_msgs/OccupancyGrid.h>
|
|
#include <nav_msgs/Odometry.h>
|
|
#include <ros/ros.h>
|
|
|
|
class Speller : public QThread {
|
|
Q_OBJECT
|
|
public:
|
|
explicit Speller(int argc, char **argv);
|
|
~Speller();
|
|
const std::map<float, int> frequency = {
|
|
{4.286f, 14}, {5.0f, 12}, {6.0f, 10}, {7.5f, 8}};
|
|
MapView *window;
|
|
|
|
private:
|
|
int argc;
|
|
char **argv;
|
|
void run() override;
|
|
|
|
enum Map_Type { SQUARE, HORIZONTAL, VERTICAL };
|
|
int in_view;
|
|
|
|
ros::NodeHandle *nh;
|
|
ros::Publisher pub_goal;
|
|
ros::Subscriber sub_pose;
|
|
ros::ServiceClient map_client;
|
|
|
|
nav_msgs::OccupancyGrid map;
|
|
geometry_msgs::PoseStamped pose;
|
|
geometry_msgs::Pose pose_current;
|
|
|
|
struct insight_data *buf;
|
|
int buf_len = 1000;
|
|
|
|
uint8_t *map_tex;
|
|
volatile int map_loading_done;
|
|
|
|
volatile int spelling;
|
|
|
|
void poseCB(nav_msgs::Odometry::ConstPtr &msg);
|
|
__inline__ void init_ble();
|
|
__inline__ void get_ble_data();
|
|
__inline__ void init_ros();
|
|
__inline__ void load_map();
|
|
|
|
private slots:
|
|
void keyEvent(QKeyEvent *key);
|
|
void map_loaded();
|
|
signals:
|
|
void load_texture(int, Vertex *, QImage);
|
|
};
|
|
#endif
|