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>
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 
17 namespace rm_referee
18 {
19 class UiBase
20 {
21 public:
22  explicit UiBase(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
23  std::deque<Graph>* character_queue = nullptr)
24  : base_(base), tf_listener_(tf_buffer_)
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];
55  int tx_len_;
56 
57 protected:
60  static int id_;
61  std::deque<Graph>* graph_queue_;
62  std::deque<Graph>* character_queue_;
65 
69 };
70 
71 class GroupUiBase : public UiBase
72 {
73 public:
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 
92 protected:
93  std::map<std::string, Graph*> graph_vector_;
94  std::map<std::string, Graph*> character_vector_;
95 };
96 
97 class FixedUi : public GroupUiBase
98 {
99 public:
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
XmlRpc::XmlRpcValue::size
int size() const
rm_referee::FixedUi::FixedUi
FixedUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition: ui_base.h:100
rm_referee::GroupUiBase::sendUi
void sendUi(const ros::Time &time) override
Definition: ui_base.cpp:252
heat_limit.h
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::UiBase::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: ui_base.h:64
rm_referee::Base
Definition: data.h:142
rm_referee::FixedUi::update_fixed_ui_times
int update_fixed_ui_times
Definition: ui_base.h:118
rm_referee::UiBase::updateManualCmdData
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time &last_get_data_time)
Definition: ui_base.h:39
rm_referee
Definition: data.h:100
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::UiBase::UiBase
UiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition: ui_base.h:22
rm_referee::UiBase::erasure
virtual void erasure()
Definition: ui_base.cpp:32
rm_referee::GroupUiBase::~GroupUiBase
~GroupUiBase()=default
ros.h
rm_referee::UiBase::k_cmd_id_length_
const int k_cmd_id_length_
Definition: ui_base.h:68
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::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
tf2_ros::TransformListener
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::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: ui_base.h:63
rm_referee::UiBase::delay_
ros::Duration delay_
Definition: ui_base.h:67
rm_referee::FixedUi
Definition: ui_base.h:97
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::GroupUiBase::character_vector_
std::map< std::string, Graph * > character_vector_
Definition: ui_base.h:94
rm_referee::UiBase::updateForQueue
virtual void updateForQueue()
Definition: ui_base.cpp:38
rm_referee::GroupUiBase::GroupUiBase
GroupUiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition: ui_base.h:74
rm_referee::UiBase::last_send_
ros::Time last_send_
Definition: ui_base.h:66
rm_referee::UiBase
Definition: ui_base.h:19
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
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
tf2_ros::Buffer
rm_referee::GroupUiBase::display
void display(bool check_repeat=true) override
Definition: ui_base.cpp:200
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
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::GroupUiBase
Definition: ui_base.h:71
rm_referee::GroupUiBase::erasure
void erasure() override
Definition: ui_base.cpp:82
rm_referee::UiBase::sendSingleGraph
void sendSingleGraph(const ros::Time &time, Graph *graph)
Definition: ui_base.cpp:185
rm_referee::UiBase::updateManualCmdData
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data)
Definition: ui_base.h:38
transform_listener.h
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
rm_referee::GroupUiBase::updateForQueue
void updateForQueue() override
Definition: ui_base.cpp:91
graph.h
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::UiBase::sendSerial
void sendSerial(const ros::Time &time, int data_len)
Definition: ui_base.cpp:352
rm_referee::UiBase::~UiBase
~UiBase()=default
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::UiBase::graph_
Graph * graph_
Definition: ui_base.h:59
ros::Duration
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
XmlRpc::XmlRpcValue
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
ori_tool.h


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