rm_control
Loading...
Searching...
No Matches
time_change_ui.h
Go to the documentation of this file.
1//
2// Created by llljjjqqq on 22-11-4.
3//
4
5#pragma once
6
8
9namespace rm_referee
10{
11class TimeChangeUi : public UiBase
12{
13public:
14 explicit TimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
15 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
16 : UiBase(rpc_value, base, graph_queue, character_queue)
17 {
18 graph_ = new Graph(rpc_value["config"], base_, id_++);
19 }
20 void update() override;
21 void updateForQueue() override;
22 virtual void updateConfig(){};
23};
24
26{
27public:
28 explicit TimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
29 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
30 : GroupUiBase(rpc_value, base, graph_queue, character_queue)
31 {
32 graph_name_ = graph_name;
33 }
34 void update() override;
35 void updateForQueue() override;
36 virtual void updateConfig(){};
37
38protected:
39 std::string graph_name_;
40};
41
43{
44public:
45 explicit CapacitorTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
46 std::deque<Graph>* character_queue)
47 : TimeChangeUi(rpc_value, base, "capacitor", graph_queue, character_queue){};
48 void add() override;
49 void updateRemainCharge(const double remain_charge, const ros::Time& time);
50
51private:
52 void updateConfig() override;
53 double remain_charge_;
54};
55
57{
58public:
59 explicit RelocalizeProgressTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
60 std::deque<Graph>* character_queue)
61 : TimeChangeUi(rpc_value, base, "relocalize", graph_queue, character_queue)
62 {
63 }
64 void add() override;
65 void updateRelocalizeProgress(const double data, const ros::Time& time);
66
67private:
68 void updateConfig() override;
69 double relocalize_progress_;
70};
71
73{
74public:
75 explicit EffortTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
76 std::deque<Graph>* character_queue)
77 : TimeChangeUi(rpc_value, base, "effort", graph_queue, character_queue){};
78 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
79
80private:
81 void updateConfig() override;
82 double joint_effort_;
83 std::string joint_name_;
84};
85
87{
88public:
89 explicit ProgressTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
90 std::deque<Graph>* character_queue)
91 : TimeChangeUi(rpc_value, base, "progress", graph_queue, character_queue){};
92 void updateEngineerUiData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time& last_get_data_time);
93
94private:
95 void updateConfig() override;
96 uint32_t finished_data_, total_steps_;
97 std::string step_name_;
98};
99
101{
102public:
103 explicit DartStatusTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
104 std::deque<Graph>* character_queue)
105 : TimeChangeUi(rpc_value, base, "dart", graph_queue, character_queue){};
106 void updateDartClientCmd(const rm_msgs::DartClientCmd::ConstPtr data, const ros::Time& last_get_data_time);
107
108private:
109 void updateConfig() override;
110 uint8_t dart_launch_opening_status_;
111};
112
114{
115public:
116 explicit RotationTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
117 std::deque<Graph>* character_queue)
118 : TimeChangeUi(rpc_value, base, "rotation", graph_queue, character_queue)
119 {
120 if (rpc_value.hasMember("data"))
121 {
122 XmlRpc::XmlRpcValue data = rpc_value["data"];
123 try
124 {
125 arc_scale_ = static_cast<int>(data["scale"]);
126 gimbal_reference_frame_ = static_cast<std::string>(data["gimbal_reference_frame"]);
127 chassis_reference_frame_ = static_cast<std::string>(data["chassis_reference_frame"]);
128 }
129 catch (XmlRpc::XmlRpcException& e)
130 {
131 ROS_FATAL_STREAM("Exception raised by XmlRpc while reading the "
132 << "configuration: " << e.getMessage() << ".\n"
133 << "Please check configuration is exit");
134 }
135 }
136 else
137 ROS_WARN("RotationTimeChangeUi config 's member 'data' not defined.");
138 };
139 void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr data);
140
141private:
142 void updateConfig() override;
143 int arc_scale_;
144 std::string gimbal_reference_frame_, chassis_reference_frame_;
145 uint8_t chassis_mode_;
146};
147
149{
150public:
151 explicit LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
152 std::deque<Graph>* character_queue)
153 : TimeChangeGroupUi(rpc_value, base, "lane_line", graph_queue, character_queue)
154 {
155 if (rpc_value.hasMember("data"))
156 {
157 XmlRpc::XmlRpcValue& data = rpc_value["data"];
158 robot_radius_ = data["radius"];
159 robot_height_ = data["height"];
160 camera_range_ = data["camera_range"];
161 surface_coefficient_ = data["surface_coefficient"];
162 }
163 else
164 ROS_WARN("LaneLineTimeChangeGroupUi config 's member 'data' not defined.");
165
166 if (rpc_value.hasMember("reference_frame"))
167 {
168 reference_frame_ = static_cast<std::string>(rpc_value["reference_frame"]);
169 }
170 else
171 ROS_WARN("LaneLineTimeChangeGroupUi config 's member 'reference_frame' not defined.");
172
173 graph_vector_.insert(
174 std::pair<std::string, Graph*>(graph_name_ + "_left", new Graph(rpc_value["config"], base_, id_++)));
175 graph_vector_.insert(
176 std::pair<std::string, Graph*>(graph_name_ + "_right", new Graph(rpc_value["config"], base_, id_++)));
177
178 for (auto it : graph_vector_)
179 lane_line_double_graph_.push_back(it.second);
180 }
181 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
182
183protected:
184 std::string reference_frame_;
185 double robot_radius_, robot_height_, camera_range_, surface_coefficient_ = 0.5;
186 double pitch_angle_ = 0., screen_x_ = 1920, screen_y_ = 1080;
187 double end_point_a_angle_, end_point_b_angle_;
188
189private:
190 void updateConfig() override;
191
192 std::vector<Graph*> lane_line_double_graph_;
193};
194
196{
197public:
198 explicit BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
199 std::deque<Graph>* character_queue)
200 : TimeChangeGroupUi(rpc_value, base, "balance_pitch", graph_queue, character_queue)
201 {
202 XmlRpc::XmlRpcValue config;
203
204 config["type"] = "line";
205 if (rpc_value["config"].hasMember("color"))
206 config["color"] = rpc_value["config"]["color"];
207 else
208 config["color"] = "cyan";
209 if (rpc_value["config"].hasMember("width"))
210 config["width"] = rpc_value["config"]["width"];
211 else
212 config["width"] = 2;
213 if (rpc_value["config"].hasMember("delay"))
214 config["delay"] = rpc_value["config"]["delay"];
215 else
216 config["delay"] = 0.2;
217
218 XmlRpc::XmlRpcValue data = rpc_value["data"];
219 ROS_ASSERT(data.hasMember("centre_point") && data.hasMember("bottom_angle") && data.hasMember("length"));
220 centre_point_[0] = static_cast<int>(data["centre_point"][0]);
221 centre_point_[1] = static_cast<int>(data["centre_point"][1]);
222 bottom_angle_ = data["bottom_angle"];
223 length_ = data["length"];
224 triangle_left_point_[0] = centre_point_[0] - length_ * sin(bottom_angle_ / 2);
225 triangle_left_point_[1] = centre_point_[1] + length_ * cos(bottom_angle_ / 2);
226 triangle_right_point_[0] = centre_point_[0] + length_ * sin(bottom_angle_ / 2);
227 triangle_right_point_[1] = centre_point_[1] + length_ * cos(bottom_angle_ / 2);
228
229 config["start_position"][0] = centre_point_[0] - length_;
230 config["start_position"][1] = centre_point_[1];
231 config["end_position"][0] = centre_point_[0] + length_;
232 config["end_position"][1] = centre_point_[1];
233 graph_vector_.insert(std::make_pair<std::string, Graph*>("bottom", new Graph(config, base_, id_++)));
234
235 config["start_position"][0] = centre_point_[0];
236 config["start_position"][1] = centre_point_[1];
237 config["end_position"][0] = triangle_left_point_[0];
238 config["end_position"][1] = triangle_left_point_[1];
239 graph_vector_.insert(std::make_pair<std::string, Graph*>("triangle_left_side", new Graph(config, base_, id_++)));
240
241 config["start_position"][0] = centre_point_[0];
242 config["start_position"][1] = centre_point_[1];
243 config["end_position"][0] = triangle_right_point_[0];
244 config["end_position"][1] = triangle_right_point_[1];
245 graph_vector_.insert(std::make_pair<std::string, Graph*>("triangle_right_side", new Graph(config, base_, id_++)));
246 }
247
248 void calculatePointPosition(const rm_msgs::BalanceStateConstPtr& data, const ros::Time& time);
249
250private:
251 void updateConfig() override;
252
253 int centre_point_[2], triangle_left_point_[2], triangle_right_point_[2], length_;
254 double bottom_angle_;
255};
256
258{
259public:
260 explicit PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
261 std::deque<Graph>* character_queue)
262 : TimeChangeUi(rpc_value, base, "pitch", graph_queue, character_queue){};
263 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
264
265private:
266 void updateConfig() override;
267 double pitch_angle_ = 0.;
268};
269
271{
272public:
273 explicit ImageTransmissionAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base,
274 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
275 : TimeChangeUi(rpc_value, base, "image_transmission", graph_queue, character_queue){};
276 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
277
278private:
279 void updateConfig() override;
280 double image_transmission_angle_ = 0.;
281};
282
284{
285public:
286 explicit JointPositionTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
287 std::deque<Graph>* character_queue, std::string name)
288 : TimeChangeUi(rpc_value, base, name, graph_queue, character_queue)
289 {
290 if (rpc_value.hasMember("data"))
291 {
292 XmlRpc::XmlRpcValue data = rpc_value["data"];
293 min_val_ = static_cast<double>(data["min_val"]);
294 max_val_ = static_cast<double>(data["max_val"]);
295 direction_ = static_cast<std::string>(data["direction"]);
296 length_ = static_cast<double>(data["line_length"]);
297 }
298 name_ = name;
299 };
300 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
301
302private:
303 void updateConfig() override;
304 std::string name_, direction_;
305 double max_val_, min_val_, current_val_, length_;
306};
307
309{
310public:
311 explicit BulletTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
312 std::deque<Graph>* character_queue)
313 : TimeChangeUi(rpc_value, base, "remaining_bullet", graph_queue, character_queue){};
314 void updateBulletData(const rm_msgs::BulletAllowance& data, const ros::Time& time);
315 void reset();
316
317private:
318 void updateConfig() override;
319 int bullet_allowance_num_17_mm_, bullet_allowance_num_42_mm_, bullet_num_17_mm_{ 0 }, bullet_num_42_mm_{ 0 };
320};
321
323{
324public:
325 explicit TargetDistanceTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
326 std::deque<Graph>* character_queue)
327 : TimeChangeUi(rpc_value, base, "target_distance", graph_queue, character_queue){};
328 void updateTargetDistanceData(const rm_msgs::TrackData::ConstPtr& data);
329
330private:
331 void updateConfig() override;
332 double target_distance_;
333};
334
336{
337public:
338 explicit DeployDistanceTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
339 std::deque<Graph>* character_queue)
340 : TimeChangeUi(rpc_value, base, "deploy_distance", graph_queue, character_queue){};
341 void updateDeployDistanceData(const geometry_msgs::PointConstPtr& data);
342
343private:
344 void updateConfig() override;
345 double deploy_distance_{};
346};
347
349{
350public:
351 explicit HeroLegTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
352 std::deque<Graph>* character_queue)
353 : TimeChangeUi(rpc_value, base, "hero_leg_feedforward_countdown", graph_queue, character_queue)
354 {
355 }
356 void updateFeedforwardCountdown(int feedforward_countdown);
357
358private:
359 void updateConfig() override;
360 int feedforward_countdown_{};
361};
363{
364public:
365 explicit DroneTowardsTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
366 std::deque<Graph>* character_queue)
367 : TimeChangeGroupUi(rpc_value, base, "drone_towards", graph_queue, character_queue)
368 {
369 if (rpc_value.hasMember("data"))
370 {
371 XmlRpc::XmlRpcValue& data = rpc_value["data"];
372 ori_x_ = static_cast<int>(data["ori_x"]);
373 ori_y_ = static_cast<int>(data["ori_y"]);
374 }
375 else
376 ROS_WARN("DroneTowardsTimeChangeGroupUi config 's member 'data' not defined.");
377
378 graph_vector_.insert(
379 std::pair<std::string, Graph*>(graph_name_ + "_mid", new Graph(rpc_value["config"], base_, id_++)));
380 graph_vector_.insert(
381 std::pair<std::string, Graph*>(graph_name_ + "_left", new Graph(rpc_value["config"], base_, id_++)));
382 graph_vector_.insert(
383 std::pair<std::string, Graph*>(graph_name_ + "_right", new Graph(rpc_value["config"], base_, id_++)));
384 };
385 void updateTowardsData(const geometry_msgs::PoseStampedConstPtr& data);
386
387private:
388 void updateConfig() override;
389 int ori_x_, ori_y_;
390 double angle_;
391 int mid_line_x1_, mid_line_y1_, mid_line_x2_, mid_line_y2_, left_line_x2_, left_line_y2_, right_line_x2_,
392 right_line_y2_;
393};
394
396{
397public:
398 explicit FriendBulletsTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
399 std::deque<Graph>* character_queue)
400 : TimeChangeGroupUi(rpc_value, base, "friend_bullets", graph_queue, character_queue)
401 {
402 graph_vector_.insert(std::pair<std::string, Graph*>("hero", new Graph(rpc_value["config"], base_, id_++)));
403 graph_vector_.insert(std::pair<std::string, Graph*>("standard3", new Graph(rpc_value["config"], base_, id_++)));
404 graph_vector_.insert(std::pair<std::string, Graph*>("standard4", new Graph(rpc_value["config"], base_, id_++)));
405 graph_vector_.insert(std::pair<std::string, Graph*>("standard5", new Graph(rpc_value["config"], base_, id_++)));
406 int ui_start_y = 0;
407 for (auto it = graph_vector_.begin(); it != graph_vector_.end(); ++it)
408 {
409 if (it == graph_vector_.begin())
410 ui_start_y = it->second->getConfig().start_y;
411 else
412 {
413 ui_start_y -= 40;
414 it->second->setStartY(ui_start_y);
415 }
416 }
417 };
418 void updateBulletsData(const rm_referee::BulletNumData& data);
419
420private:
421 void updateConfig() override;
422 int hero_bullets_{ 1 }, standard3_bullets_{ 3 }, standard4_bullets_{ 4 }, standard5_bullets_{ 5 };
423};
424
426{
427public:
428 explicit TargetHpTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
429 std::deque<Graph>* character_queue)
430 : TimeChangeUi(rpc_value, base, "target_hp", graph_queue, character_queue)
431 {
432 if (rpc_value.hasMember("enemy_id"))
433 {
434 XmlRpc::XmlRpcValue& enemy_id = rpc_value["enemy_id"];
435 for (int i = 0; i < enemy_id.size(); i++)
436 {
437 int id = static_cast<int>(enemy_id[i]);
438 enemy_robot_hp_[id] = 0;
439 }
440 }
441 }
442 void setEnemyHp(const rm_msgs::GameRobotHp& data);
443 void updateTrackID(int id);
444 void updateTargeHptData();
445
446private:
447 void updateConfig() override;
448 std::map<int, int> enemy_robot_hp_;
449 int target_hp_{}, target_id_{};
450};
451
452} // namespace rm_referee
Definition time_change_ui.h:196
BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:198
Definition data.h:120
Definition time_change_ui.h:309
BulletTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:311
Definition time_change_ui.h:43
CapacitorTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:45
void updateRemainCharge(const double remain_charge, const ros::Time &time)
Definition time_change_ui.cpp:76
void add() override
Definition time_change_ui.cpp:50
Definition time_change_ui.h:101
void updateDartClientCmd(const rm_msgs::DartClientCmd::ConstPtr data, const ros::Time &last_get_data_time)
Definition time_change_ui.cpp:183
DartStatusTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:103
Definition time_change_ui.h:336
DeployDistanceTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:338
Definition time_change_ui.h:363
DroneTowardsTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:365
Definition time_change_ui.h:73
void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time &time)
Definition time_change_ui.cpp:125
EffortTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:75
Definition time_change_ui.h:396
FriendBulletsTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:398
Definition graph.h:13
Definition ui_base.h:72
Definition time_change_ui.h:349
HeroLegTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:351
Definition time_change_ui.h:271
ImageTransmissionAngleTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:273
Definition time_change_ui.h:284
JointPositionTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue, std::string name)
Definition time_change_ui.h:286
Definition time_change_ui.h:149
double end_point_a_angle_
Definition time_change_ui.h:187
double camera_range_
Definition time_change_ui.h:185
LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:151
std::string reference_frame_
Definition time_change_ui.h:184
Definition time_change_ui.h:258
PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:260
Definition time_change_ui.h:87
void updateEngineerUiData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time &last_get_data_time)
Definition time_change_ui.cpp:154
ProgressTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:89
Definition time_change_ui.h:57
RelocalizeProgressTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:59
void add() override
Definition time_change_ui.cpp:81
void updateRelocalizeProgress(const double data, const ros::Time &time)
Definition time_change_ui.cpp:107
Definition time_change_ui.h:114
RotationTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:116
Definition time_change_ui.h:323
TargetDistanceTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:325
Definition time_change_ui.h:426
TargetHpTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:428
Definition time_change_ui.h:26
std::string graph_name_
Definition time_change_ui.h:39
virtual void updateConfig()
Definition time_change_ui.h:36
TimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &graph_name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:28
void update() override
Definition time_change_ui.cpp:18
void updateForQueue() override
Definition time_change_ui.cpp:40
Definition time_change_ui.h:12
TimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &graph_name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:14
void updateForQueue() override
Definition time_change_ui.cpp:28
virtual void updateConfig()
Definition time_change_ui.h:22
void update() override
Definition time_change_ui.cpp:11
Definition ui_base.h:20
Graph * graph_
Definition ui_base.h:59
static int id_
Definition ui_base.h:60
Base & base_
Definition ui_base.h:58
Definition data.h:109