rm_control
Loading...
Searching...
No Matches
ui_base.h
Go to the documentation of this file.
1//
2// Created by llljjjqqq on 22-11-4.
3//
4#pragma once
5
6#include <ros/ros.h>
7#include <tf/transform_listener.h>
8#include <Eigen/Dense>
9#include <cmath>
10#include <deque>
11#include <rm_common/ori_tool.h>
13#include <rm_msgs/StatusChangeRequest.h>
14
15#include "rm_referee/ui/graph.h"
16
17namespace rm_referee
18{
19class UiBase
20{
21public:
22 explicit UiBase(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
23 std::deque<Graph>* character_queue = nullptr)
25 {
26 if (rpc_value.hasMember("config"))
27 if (rpc_value["config"].hasMember("delay"))
28 delay_ = ros::Duration(static_cast<double>(rpc_value["config"]["delay"]));
29 graph_queue_ = graph_queue;
30 character_queue_ = character_queue;
31 };
32 ~UiBase() = default;
33 virtual void add();
34 virtual void update();
35 virtual void updateForQueue();
36 virtual void erasure();
37 virtual void addForQueue(int add_times = 1);
38 virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data){};
39 virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time& last_get_data_time){};
40 virtual void sendUi(const ros::Time& time);
41
42 void sendCharacter(const ros::Time& time, Graph* graph);
43 void sendSingleGraph(const ros::Time& time, Graph* graph);
44
45 void sendSerial(const ros::Time& time, int data_len);
46 void clearTxBuffer();
47
48 virtual void display(bool check_repeat = true);
49 virtual void displayTwice(bool check_repeat = true);
50 virtual void display(const ros::Time& time);
51 void display(const ros::Time& time, bool state, bool once = false);
52 void pack(uint8_t* tx_buffer, uint8_t* data, int cmd_id, int len) const;
53
54 uint8_t tx_buffer_[127];
56
57protected:
60 static int id_;
61 std::deque<Graph>* graph_queue_;
62 std::deque<Graph>* character_queue_;
63 tf2_ros::Buffer tf_buffer_;
64 tf2_ros::TransformListener tf_listener_;
65
66 ros::Time last_send_;
67 ros::Duration delay_ = ros::Duration(0.);
69};
70
71class GroupUiBase : public UiBase
72{
73public:
74 explicit GroupUiBase(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
75 std::deque<Graph>* character_queue = nullptr)
76 : UiBase(rpc_value, base, graph_queue, character_queue){};
77 ~GroupUiBase() = default;
78 void add() override;
79 void update() override;
80 void updateForQueue() override;
81 void erasure() override;
82 void addForQueue(int add_times = 1) override;
83 void sendUi(const ros::Time& time) override;
84 void sendDoubleGraph(const ros::Time& time, Graph* graph0, Graph* graph1);
85 void sendFiveGraph(const ros::Time& time, Graph* graph0, Graph* graph1, Graph* graph2, Graph* graph3, Graph* graph4);
86 void sendSevenGraph(const ros::Time& time, Graph* graph0, Graph* graph1, Graph* graph2, Graph* graph3, Graph* graph4,
87 Graph* graph5, Graph* graph6);
88 void display(bool check_repeat = true) override;
89 void display(const ros::Time& time) override;
90 void displayTwice(bool check_repeat = true) override;
91
92protected:
93 std::map<std::string, Graph*> graph_vector_;
94 std::map<std::string, Graph*> character_vector_;
95};
96
97class FixedUi : public GroupUiBase
98{
99public:
100 explicit FixedUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
101 std::deque<Graph>* character_queue = nullptr)
102 : GroupUiBase(rpc_value, base, graph_queue, character_queue)
103 {
104 for (int i = 0; i < static_cast<int>(rpc_value.size()); i++)
105 {
106 if (rpc_value[i]["config"]["type"] == "string")
107 {
108 ROS_INFO_STREAM("string FixedUi:" << rpc_value[i]["name"]);
109 character_vector_.insert(
110 std::pair<std::string, Graph*>(rpc_value[i]["name"], new Graph(rpc_value[i]["config"], base_, id_++)));
111 }
112 else
113 graph_vector_.insert(
114 std::pair<std::string, Graph*>(rpc_value[i]["name"], new Graph(rpc_value[i]["config"], base_, id_++)));
115 }
116 };
117 void updateForQueue() override;
119};
120
121} // namespace rm_referee
Definition data.h:112
Definition ui_base.h:98
void updateForQueue() override
Definition ui_base.cpp:321
int update_fixed_ui_times
Definition ui_base.h:118
FixedUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:100
Definition graph.h:13
Definition ui_base.h:72
void erasure() override
Definition ui_base.cpp:82
std::map< std::string, Graph * > character_vector_
Definition ui_base.h:94
void display(bool check_repeat=true) override
Definition ui_base.cpp:200
void updateForQueue() override
Definition ui_base.cpp:91
void add() override
Definition ui_base.cpp:45
void sendDoubleGraph(const ros::Time &time, Graph *graph0, Graph *graph1)
Definition ui_base.cpp:263
std::map< std::string, Graph * > graph_vector_
Definition ui_base.h:93
void displayTwice(bool check_repeat=true) override
Definition ui_base.cpp:222
void sendSevenGraph(const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4, Graph *graph5, Graph *graph6)
Definition ui_base.cpp:299
void sendUi(const ros::Time &time) override
Definition ui_base.cpp:252
void addForQueue(int add_times=1) override
Definition ui_base.cpp:54
void update() override
Definition ui_base.cpp:73
void sendFiveGraph(const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4)
Definition ui_base.cpp:279
GroupUiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:74
Definition ui_base.h:20
virtual void add()
Definition ui_base.cpp:10
std::deque< Graph > * graph_queue_
Definition ui_base.h:61
uint8_t tx_buffer_[127]
Definition ui_base.h:54
virtual void display(bool check_repeat=true)
Definition ui_base.cpp:105
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time &last_get_data_time)
Definition ui_base.h:39
Graph * graph_
Definition ui_base.h:59
const int k_frame_length_
Definition ui_base.h:68
tf2_ros::TransformListener tf_listener_
Definition ui_base.h:64
void pack(uint8_t *tx_buffer, uint8_t *data, int cmd_id, int len) const
Definition ui_base.cpp:339
void sendSerial(const ros::Time &time, int data_len)
Definition ui_base.cpp:352
ros::Time last_send_
Definition ui_base.h:66
ros::Duration delay_
Definition ui_base.h:67
void sendSingleGraph(const ros::Time &time, Graph *graph)
Definition ui_base.cpp:185
std::deque< Graph > * character_queue_
Definition ui_base.h:62
void clearTxBuffer()
Definition ui_base.cpp:366
virtual void sendUi(const ros::Time &time)
Definition ui_base.cpp:151
virtual void erasure()
Definition ui_base.cpp:32
virtual void update()
Definition ui_base.cpp:26
const int k_header_length_
Definition ui_base.h:68
void sendCharacter(const ros::Time &time, Graph *graph)
Definition ui_base.cpp:162
const int k_cmd_id_length_
Definition ui_base.h:68
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data)
Definition ui_base.h:38
tf2_ros::Buffer tf_buffer_
Definition ui_base.h:63
virtual void updateForQueue()
Definition ui_base.cpp:38
static int id_
Definition ui_base.h:60
virtual void addForQueue(int add_times=1)
Definition ui_base.cpp:16
const int k_tail_length_
Definition ui_base.h:68
virtual void displayTwice(bool check_repeat=true)
Definition ui_base.cpp:114
int tx_len_
Definition ui_base.h:55
Base & base_
Definition ui_base.h:58
UiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:22
Definition data.h:101