2019-12-09 14:24:24 +05:30

73 lines
1.7 KiB
C++

#ifndef SPELLER
#define SPELLER
#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_Shape { SQUARE, HORIZONTAL, VERTICAL };
enum Classify_Type { TOP_RIGHT = 1, TOP_LEFT, BOTTOM_LEFT, BOTTOM_RIGHT };
QImage *curr_map;
QRect *area_displayed;
uint8_t *map_tex_buffer;
int map_shape;
int classifier_result;
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 = 100;
volatile int map_loading_done;
volatile int spelling;
void reconfigure_map(int, int);
void poseCB(nav_msgs::Odometry::ConstPtr &msg);
__inline__ void init_ble();
__inline__ void get_ble_data();
__inline__ void init_ros();
__inline__ void load_map();
void classify(int len, struct insight_data *buf);
QPoint me;
private slots:
void keyEvent(QKeyEvent *key);
void map_loaded();
void mouse_press(QMouseEvent *);
signals:
void load_texture(int, Vertex *, QImage *);
};
#endif