ui_base.cpp
Go to the documentation of this file.
1 //
2 // Created by llljjjqqq on 22-11-4.
3 //
4 
6 
7 namespace rm_referee
8 {
9 int UiBase::id_(2);
11 {
13  displayTwice(false);
14 }
15 
16 void UiBase::addForQueue(int add_times)
17 {
18  for (int i = 0; i < add_times; i++)
19  {
21  graph_queue_->push_back(*graph_);
23  }
24 }
25 
27 {
29  display();
30 }
31 
33 {
35  displayTwice(false);
36 }
37 
39 {
40  if (graph_->isString())
41  character_queue_->push_back(*graph_);
42  else
43  graph_queue_->push_back(*graph_);
44 }
46 {
47  for (auto graph : graph_vector_)
48  graph.second->setOperation(rm_referee::GraphOperation::ADD);
49  for (auto character : character_vector_)
50  character.second->setOperation(rm_referee::GraphOperation::ADD);
51  displayTwice(false);
52 }
53 
54 void GroupUiBase::addForQueue(int add_times)
55 {
56  for (int i = 0; i < add_times; i++)
57  {
58  for (auto graph : graph_vector_)
59  {
60  graph.second->setOperation(rm_referee::GraphOperation::ADD);
61  graph_queue_->push_back(*graph.second);
63  }
64  for (auto graph : character_vector_)
65  {
66  graph.second->setOperation(rm_referee::GraphOperation::ADD);
67  character_queue_->push_back(*graph.second);
69  }
70  }
71 }
72 
74 {
75  for (auto graph : graph_vector_)
76  graph.second->setOperation(rm_referee::GraphOperation::UPDATE);
77  for (auto character : character_vector_)
78  character.second->setOperation(rm_referee::GraphOperation::UPDATE);
79  display();
80 }
81 
83 {
84  for (auto graph : graph_vector_)
86  for (auto character : character_vector_)
87  character.second->setOperation(rm_referee::GraphOperation::DELETE);
88  displayTwice(false);
89 }
90 
92 {
93  for (auto it : character_vector_)
94  {
95  it.second->setOperation(rm_referee::GraphOperation::UPDATE);
96  character_queue_->push_back(*it.second);
97  }
98  for (auto it : graph_vector_)
99  {
100  it.second->setOperation(rm_referee::GraphOperation::UPDATE);
101  graph_queue_->push_back(*it.second);
102  }
103 }
104 
105 void UiBase::display(bool check_repeat)
106 {
107  if (check_repeat)
108  if (graph_->isRepeated())
109  return;
112 }
113 
114 void UiBase::displayTwice(bool check_repeat)
115 {
116  if (check_repeat)
117  if (graph_->isRepeated())
118  return;
120  for (int i = 0; i < 2; ++i)
122 }
123 
124 void UiBase::display(const ros::Time& time)
125 {
126  if (time - last_send_ < delay_)
127  return;
128  display();
129 }
130 
131 void UiBase::display(const ros::Time& time, bool state, bool once)
132 {
133  if (once)
134  {
135  if (state)
137  else
139  }
140  else if (state && time - last_send_ > delay_)
141  {
142  // todo: has problem in this case
143  ROS_INFO("%f %.3f", last_send_.toSec(), delay_.toSec());
147  }
148  displayTwice();
149 }
150 
151 void UiBase::sendUi(const ros::Time& time)
152 {
153  if (base_.robot_id_ == 0 || base_.client_id_ == 0)
154  return;
155 
156  if (graph_->isString())
157  sendCharacter(time, graph_);
158  else
159  sendSingleGraph(time, graph_);
160 }
161 
163 {
164  int data_len;
165  std::string characters = graph->getCharacters();
166  rm_referee::CharacterData tx_data;
167  data_len = static_cast<int>(sizeof(rm_referee::CharacterData));
168 
169  tx_data.header.sender_id = base_.robot_id_;
170  tx_data.header.receiver_id = base_.client_id_;
171  tx_data.config = graph->getConfig();
172 
173  for (int i = 0; i < 30; i++)
174  {
175  if (i < static_cast<int>(characters.size()))
176  tx_data.content[i] = characters[i];
177  else
178  tx_data.content[i] = ' ';
179  }
180  tx_data.header.data_cmd_id = rm_referee::DataCmdId::CLIENT_CHARACTER_CMD;
181  pack(tx_buffer_, reinterpret_cast<uint8_t*>(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len);
182  sendSerial(time, data_len);
183 }
184 
185 void UiBase::sendSingleGraph(const ros::Time& time, Graph* graph)
186 {
187  int data_len;
188  rm_referee::SingleGraphData tx_data;
189  data_len = static_cast<int>(sizeof(rm_referee::SingleGraphData));
190 
191  tx_data.header.sender_id = base_.robot_id_;
192  tx_data.header.receiver_id = base_.client_id_;
193  tx_data.config = graph->getConfig();
194 
195  tx_data.header.data_cmd_id = rm_referee::DataCmdId::CLIENT_GRAPH_SINGLE_CMD;
196  pack(tx_buffer_, reinterpret_cast<uint8_t*>(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len);
197  sendSerial(time, data_len);
198 }
199 
200 void GroupUiBase::display(bool check_repeat)
201 {
202  if (check_repeat)
203  {
204  bool is_repeat = true;
205  for (auto it : graph_vector_)
206  if (!it.second->isRepeated())
207  is_repeat = false;
208  for (auto it : character_vector_)
209  if (!it.second->isRepeated())
210  is_repeat = false;
211  if (is_repeat)
212  return;
213  }
214 
215  for (auto it : graph_vector_)
216  it.second->updateLastConfig();
217  for (auto it : character_vector_)
218  it.second->updateLastConfig();
220 }
221 
222 void GroupUiBase::displayTwice(bool check_repeat)
223 {
224  if (check_repeat)
225  {
226  bool is_repeat = true;
227  for (auto it : graph_vector_)
228  if (!it.second->isRepeated())
229  is_repeat = false;
230  for (auto it : character_vector_)
231  if (!it.second->isRepeated())
232  is_repeat = false;
233  if (is_repeat)
234  return;
235  }
236 
237  for (auto it : graph_vector_)
238  it.second->updateLastConfig();
239  for (auto it : character_vector_)
240  it.second->updateLastConfig();
241  for (int i = 0; i < 2; i++)
243 }
244 
246 {
247  if (time - last_send_ < delay_)
248  return;
249  display();
250 }
251 
253 {
254  if (base_.robot_id_ == 0 || base_.client_id_ == 0)
255  return;
256 
257  for (auto it : character_vector_)
258  sendCharacter(time, it.second);
259  for (auto it : graph_vector_)
260  sendSingleGraph(time, it.second);
261 }
262 
263 void GroupUiBase::sendDoubleGraph(const ros::Time& time, Graph* graph0, Graph* graph1)
264 {
265  int data_len;
266  rm_referee::DoubleGraphData tx_data;
267  data_len = static_cast<int>(sizeof(rm_referee::DoubleGraphData));
268 
269  tx_data.header.sender_id = base_.robot_id_;
270  tx_data.header.receiver_id = base_.client_id_;
271  tx_data.config[0] = graph0->getConfig();
272  tx_data.config[1] = graph1->getConfig();
273 
274  tx_data.header.data_cmd_id = rm_referee::DataCmdId::CLIENT_GRAPH_DOUBLE_CMD;
275  pack(tx_buffer_, reinterpret_cast<uint8_t*>(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len);
276  sendSerial(time, data_len);
277 }
278 
279 void GroupUiBase::sendFiveGraph(const ros::Time& time, Graph* graph0, Graph* graph1, Graph* graph2, Graph* graph3,
280  Graph* graph4)
281 {
282  int data_len;
283  rm_referee::FiveGraphData tx_data;
284  data_len = static_cast<int>(sizeof(rm_referee::FiveGraphData));
285 
286  tx_data.header.sender_id = base_.robot_id_;
287  tx_data.header.receiver_id = base_.client_id_;
288  tx_data.config[0] = graph0->getConfig();
289  tx_data.config[1] = graph1->getConfig();
290  tx_data.config[2] = graph2->getConfig();
291  tx_data.config[3] = graph3->getConfig();
292  tx_data.config[4] = graph4->getConfig();
293 
294  tx_data.header.data_cmd_id = rm_referee::DataCmdId::CLIENT_GRAPH_FIVE_CMD;
295  pack(tx_buffer_, reinterpret_cast<uint8_t*>(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len);
296  sendSerial(time, data_len);
297 }
298 
299 void GroupUiBase::sendSevenGraph(const ros::Time& time, Graph* graph0, Graph* graph1, Graph* graph2, Graph* graph3,
300  Graph* graph4, Graph* graph5, Graph* graph6)
301 {
302  int data_len;
303  rm_referee::SevenGraphData tx_data;
304  data_len = static_cast<int>(sizeof(rm_referee::SevenGraphData));
305 
306  tx_data.header.sender_id = base_.robot_id_;
307  tx_data.header.receiver_id = base_.client_id_;
308  tx_data.config[0] = graph0->getConfig();
309  tx_data.config[1] = graph1->getConfig();
310  tx_data.config[2] = graph2->getConfig();
311  tx_data.config[3] = graph3->getConfig();
312  tx_data.config[4] = graph4->getConfig();
313  tx_data.config[5] = graph5->getConfig();
314  tx_data.config[6] = graph6->getConfig();
315 
316  tx_data.header.data_cmd_id = rm_referee::DataCmdId::CLIENT_GRAPH_SEVEN_CMD;
317  pack(tx_buffer_, reinterpret_cast<uint8_t*>(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len);
318  sendSerial(time, data_len);
319 }
320 
322 {
323  while (update_fixed_ui_times < 1)
324  {
325  for (auto it : graph_vector_)
326  it.second->updateLastConfig();
327  for (auto it : character_vector_)
328  it.second->updateLastConfig();
329 
330  if (base_.robot_id_ == 0 || base_.client_id_ == 0)
331  return;
332 
334  ROS_INFO_THROTTLE(1.0, "update fixed ui");
336  }
337 }
338 
339 void UiBase::pack(uint8_t* tx_buffer, uint8_t* data, int cmd_id, int len) const
340 {
341  memset(tx_buffer, 0, k_frame_length_);
342  auto* frame_header = reinterpret_cast<FrameHeader*>(tx_buffer);
343 
344  frame_header->sof = 0xA5;
345  frame_header->data_length = len;
346  memcpy(&tx_buffer[k_header_length_], reinterpret_cast<uint8_t*>(&cmd_id), k_cmd_id_length_);
348  memcpy(&tx_buffer[k_header_length_ + k_cmd_id_length_], data, len);
350 }
351 
352 void UiBase::sendSerial(const ros::Time& time, int data_len)
353 {
355  last_send_ = time;
356  try
357  {
359  }
361  {
362  }
363  clearTxBuffer();
364 }
365 
367 {
368  for (int i = 0; i < 127; i++)
369  tx_buffer_[i] = 0;
370  tx_len_ = 0;
371 }
372 
373 } // namespace rm_referee
rm_referee::GroupUiBase::sendUi
void sendUi(const ros::Time &time) override
Definition: ui_base.cpp:252
rm_referee::UiBase::addForQueue
virtual void addForQueue(int add_times=1)
Definition: ui_base.cpp:16
rm_referee::GroupUiBase::graph_vector_
std::map< std::string, Graph * > graph_vector_
Definition: ui_base.h:93
rm_referee::Base::robot_id_
int robot_id_
Definition: data.h:148
rm_referee::FixedUi::update_fixed_ui_times
int update_fixed_ui_times
Definition: ui_base.h:118
rm_referee
Definition: data.h:100
rm_referee::Graph::getConfig
rm_referee::GraphConfig getConfig()
Definition: graph.h:25
rm_referee::CLIENT_GRAPH_SEVEN_CMD
@ CLIENT_GRAPH_SEVEN_CMD
Definition: protocol.h:94
rm_referee::UiBase::k_header_length_
const int k_header_length_
Definition: ui_base.h:68
rm_referee::UiBase::displayTwice
virtual void displayTwice(bool check_repeat=true)
Definition: ui_base.cpp:114
rm_referee::Graph::isString
bool isString()
Definition: graph.h:97
rm_referee::UiBase::erasure
virtual void erasure()
Definition: ui_base.cpp:32
rm_referee::UiBase::k_cmd_id_length_
const int k_cmd_id_length_
Definition: ui_base.h:68
rm_referee::Graph::getCharacters
std::string getCharacters()
Definition: graph.h:29
rm_referee::UiBase::display
virtual void display(bool check_repeat=true)
Definition: ui_base.cpp:105
rm_referee::GroupUiBase::update
void update() override
Definition: ui_base.cpp:73
rm_referee::Base::client_id_
int client_id_
Definition: data.h:147
TimeBase< Time, Duration >::toSec
double toSec() const
rm_referee::GroupUiBase::displayTwice
void displayTwice(bool check_repeat=true) override
Definition: ui_base.cpp:222
rm_referee::UiBase::k_frame_length_
const int k_frame_length_
Definition: ui_base.h:68
rm_referee::UiBase::character_queue_
std::deque< Graph > * character_queue_
Definition: ui_base.h:62
rm_referee::Base::appendCRC8CheckSum
void appendCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition: data.h:192
rm_referee::CLIENT_GRAPH_DOUBLE_CMD
@ CLIENT_GRAPH_DOUBLE_CMD
Definition: protocol.h:92
rm_referee::UiBase::sendUi
virtual void sendUi(const ros::Time &time)
Definition: ui_base.cpp:151
rm_referee::UiBase::pack
void pack(uint8_t *tx_buffer, uint8_t *data, int cmd_id, int len) const
Definition: ui_base.cpp:339
rm_referee::UiBase::delay_
ros::Duration delay_
Definition: ui_base.h:67
rm_referee::GroupUiBase::sendFiveGraph
void sendFiveGraph(const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4)
Definition: ui_base.cpp:279
rm_referee::UiBase::clearTxBuffer
void clearTxBuffer()
Definition: ui_base.cpp:366
rm_referee::CLIENT_CHARACTER_CMD
@ CLIENT_CHARACTER_CMD
Definition: protocol.h:95
rm_referee::GroupUiBase::character_vector_
std::map< std::string, Graph * > character_vector_
Definition: ui_base.h:94
rm_referee::Graph::isRepeated
bool isRepeated()
Definition: graph.h:93
rm_referee::UiBase::updateForQueue
virtual void updateForQueue()
Definition: ui_base.cpp:38
rm_referee::Base::appendCRC16CheckSum
void appendCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition: data.h:225
rm_referee::UiBase::last_send_
ros::Time last_send_
Definition: ui_base.h:66
rm_referee::UiBase::sendCharacter
void sendCharacter(const ros::Time &time, Graph *graph)
Definition: ui_base.cpp:162
rm_referee::UiBase::base_
Base & base_
Definition: ui_base.h:58
serial::Serial::write
size_t write(const std::string &data)
rm_referee::UiBase::k_tail_length_
const int k_tail_length_
Definition: ui_base.h:68
rm_referee::UiBase::tx_buffer_
uint8_t tx_buffer_[127]
Definition: ui_base.h:54
ui_base.h
rm_referee::GroupUiBase::display
void display(bool check_repeat=true) override
Definition: ui_base.cpp:200
rm_referee::INTERACTIVE_DATA_CMD
@ INTERACTIVE_DATA_CMD
Definition: protocol.h:70
rm_referee::Graph::setOperation
void setOperation(const rm_referee::GraphOperation &operation)
Definition: graph.h:17
rm_referee::UiBase::id_
static int id_
Definition: ui_base.h:60
rm_referee::UiBase::tx_len_
int tx_len_
Definition: ui_base.h:55
rm_referee::DELETE
@ DELETE
Definition: protocol.h:148
rm_referee::GroupUiBase::erasure
void erasure() override
Definition: ui_base.cpp:82
rm_referee::Graph::updateLastConfig
void updateLastConfig()
Definition: graph.h:101
rm_referee::CLIENT_GRAPH_FIVE_CMD
@ CLIENT_GRAPH_FIVE_CMD
Definition: protocol.h:93
rm_referee::UiBase::sendSingleGraph
void sendSingleGraph(const ros::Time &time, Graph *graph)
Definition: ui_base.cpp:185
rm_referee::GroupUiBase::updateForQueue
void updateForQueue() override
Definition: ui_base.cpp:91
ros::Time
rm_referee::UiBase::graph_queue_
std::deque< Graph > * graph_queue_
Definition: ui_base.h:61
rm_referee::FixedUi::updateForQueue
void updateForQueue() override
Definition: ui_base.cpp:321
rm_referee::CLIENT_GRAPH_SINGLE_CMD
@ CLIENT_GRAPH_SINGLE_CMD
Definition: protocol.h:91
rm_referee::UiBase::sendSerial
void sendSerial(const ros::Time &time, int data_len)
Definition: ui_base.cpp:352
rm_referee::GroupUiBase::addForQueue
void addForQueue(int add_times=1) override
Definition: ui_base.cpp:54
rm_referee::UiBase::add
virtual void add()
Definition: ui_base.cpp:10
rm_referee::Base::serial_
serial::Serial serial_
Definition: data.h:145
DurationBase< Duration >::toSec
double toSec() const
rm_referee::UPDATE
@ UPDATE
Definition: protocol.h:147
ROS_INFO
#define ROS_INFO(...)
rm_referee::UiBase::graph_
Graph * graph_
Definition: ui_base.h:59
serial::PortNotOpenedException
rm_referee::GroupUiBase::add
void add() override
Definition: ui_base.cpp:45
rm_referee::GroupUiBase::sendDoubleGraph
void sendDoubleGraph(const ros::Time &time, Graph *graph0, Graph *graph1)
Definition: ui_base.cpp:263
rm_referee::Graph
Definition: graph.h:12
rm_referee::UiBase::update
virtual void update()
Definition: ui_base.cpp:26
rm_referee::Graph::getOperation
int getOperation()
Definition: graph.h:21
rm_referee::GroupUiBase::sendSevenGraph
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
ros::Time::now
static Time now()
ROS_INFO_THROTTLE
#define ROS_INFO_THROTTLE(period,...)
rm_referee::ADD
@ ADD
Definition: protocol.h:146


rm_referee
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:49