rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
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 EffortTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
60 std::deque<Graph>* character_queue)
61 : TimeChangeUi(rpc_value, base, "effort", graph_queue, character_queue){};
62 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
63
64private:
65 void updateConfig() override;
66 double joint_effort_;
67 std::string joint_name_;
68};
69
71{
72public:
73 explicit ProgressTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
74 std::deque<Graph>* character_queue)
75 : TimeChangeUi(rpc_value, base, "progress", graph_queue, character_queue){};
76 void updateEngineerUiData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time& last_get_data_time);
77
78private:
79 void updateConfig() override;
80 uint32_t finished_data_, total_steps_;
81 std::string step_name_;
82};
83
85{
86public:
87 explicit DartStatusTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
88 std::deque<Graph>* character_queue)
89 : TimeChangeUi(rpc_value, base, "dart", graph_queue, character_queue){};
90 void updateDartClientCmd(const rm_msgs::DartClientCmd::ConstPtr data, const ros::Time& last_get_data_time);
91
92private:
93 void updateConfig() override;
94 uint8_t dart_launch_opening_status_;
95};
96
98{
99public:
100 explicit RotationTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
101 std::deque<Graph>* character_queue)
102 : TimeChangeUi(rpc_value, base, "rotation", graph_queue, character_queue)
103 {
104 if (rpc_value.hasMember("data"))
105 {
106 XmlRpc::XmlRpcValue data = rpc_value["data"];
107 try
108 {
109 arc_scale_ = static_cast<int>(data["scale"]);
110 gimbal_reference_frame_ = static_cast<std::string>(data["gimbal_reference_frame"]);
111 chassis_reference_frame_ = static_cast<std::string>(data["chassis_reference_frame"]);
112 }
113 catch (XmlRpc::XmlRpcException& e)
114 {
115 ROS_FATAL_STREAM("Exception raised by XmlRpc while reading the "
116 << "configuration: " << e.getMessage() << ".\n"
117 << "Please check configuration is exit");
118 }
119 }
120 else
121 ROS_WARN("RotationTimeChangeUi config 's member 'data' not defined.");
122 };
123 void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr data);
124
125private:
126 void updateConfig() override;
127 int arc_scale_;
128 std::string gimbal_reference_frame_, chassis_reference_frame_;
129 uint8_t chassis_mode_;
130};
131
133{
134public:
135 explicit LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
136 std::deque<Graph>* character_queue)
137 : TimeChangeGroupUi(rpc_value, base, "lane_line", graph_queue, character_queue)
138 {
139 if (rpc_value.hasMember("data"))
140 {
141 XmlRpc::XmlRpcValue& data = rpc_value["data"];
142 robot_radius_ = data["radius"];
143 robot_height_ = data["height"];
144 camera_range_ = data["camera_range"];
145 surface_coefficient_ = data["surface_coefficient"];
146 }
147 else
148 ROS_WARN("LaneLineTimeChangeGroupUi config 's member 'data' not defined.");
149
150 if (rpc_value.hasMember("reference_frame"))
151 {
152 reference_frame_ = static_cast<std::string>(rpc_value["reference_frame"]);
153 }
154 else
155 ROS_WARN("LaneLineTimeChangeGroupUi config 's member 'reference_frame' not defined.");
156
157 graph_vector_.insert(
158 std::pair<std::string, Graph*>(graph_name_ + "_left", new Graph(rpc_value["config"], base_, id_++)));
159 graph_vector_.insert(
160 std::pair<std::string, Graph*>(graph_name_ + "_right", new Graph(rpc_value["config"], base_, id_++)));
161
162 for (auto it : graph_vector_)
163 lane_line_double_graph_.push_back(it.second);
164 }
165 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
166
167protected:
168 std::string reference_frame_;
169 double robot_radius_, robot_height_, camera_range_, surface_coefficient_ = 0.5;
170 double pitch_angle_ = 0., screen_x_ = 1920, screen_y_ = 1080;
171 double end_point_a_angle_, end_point_b_angle_;
172
173private:
174 void updateConfig() override;
175
176 std::vector<Graph*> lane_line_double_graph_;
177};
178
180{
181public:
182 explicit BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
183 std::deque<Graph>* character_queue)
184 : TimeChangeGroupUi(rpc_value, base, "balance_pitch", graph_queue, character_queue)
185 {
186 XmlRpc::XmlRpcValue config;
187
188 config["type"] = "line";
189 if (rpc_value["config"].hasMember("color"))
190 config["color"] = rpc_value["config"]["color"];
191 else
192 config["color"] = "cyan";
193 if (rpc_value["config"].hasMember("width"))
194 config["width"] = rpc_value["config"]["width"];
195 else
196 config["width"] = 2;
197 if (rpc_value["config"].hasMember("delay"))
198 config["delay"] = rpc_value["config"]["delay"];
199 else
200 config["delay"] = 0.2;
201
202 XmlRpc::XmlRpcValue data = rpc_value["data"];
203 ROS_ASSERT(data.hasMember("centre_point") && data.hasMember("bottom_angle") && data.hasMember("length"));
204 centre_point_[0] = static_cast<int>(data["centre_point"][0]);
205 centre_point_[1] = static_cast<int>(data["centre_point"][1]);
206 bottom_angle_ = data["bottom_angle"];
207 length_ = data["length"];
208 triangle_left_point_[0] = centre_point_[0] - length_ * sin(bottom_angle_ / 2);
209 triangle_left_point_[1] = centre_point_[1] + length_ * cos(bottom_angle_ / 2);
210 triangle_right_point_[0] = centre_point_[0] + length_ * sin(bottom_angle_ / 2);
211 triangle_right_point_[1] = centre_point_[1] + length_ * cos(bottom_angle_ / 2);
212
213 config["start_position"][0] = centre_point_[0] - length_;
214 config["start_position"][1] = centre_point_[1];
215 config["end_position"][0] = centre_point_[0] + length_;
216 config["end_position"][1] = centre_point_[1];
217 graph_vector_.insert(std::make_pair<std::string, Graph*>("bottom", new Graph(config, base_, id_++)));
218
219 config["start_position"][0] = centre_point_[0];
220 config["start_position"][1] = centre_point_[1];
221 config["end_position"][0] = triangle_left_point_[0];
222 config["end_position"][1] = triangle_left_point_[1];
223 graph_vector_.insert(std::make_pair<std::string, Graph*>("triangle_left_side", new Graph(config, base_, id_++)));
224
225 config["start_position"][0] = centre_point_[0];
226 config["start_position"][1] = centre_point_[1];
227 config["end_position"][0] = triangle_right_point_[0];
228 config["end_position"][1] = triangle_right_point_[1];
229 graph_vector_.insert(std::make_pair<std::string, Graph*>("triangle_right_side", new Graph(config, base_, id_++)));
230 }
231
232 void calculatePointPosition(const rm_msgs::BalanceStateConstPtr& data, const ros::Time& time);
233
234private:
235 void updateConfig() override;
236
237 int centre_point_[2], triangle_left_point_[2], triangle_right_point_[2], length_;
238 double bottom_angle_;
239};
240
242{
243public:
244 explicit PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
245 std::deque<Graph>* character_queue)
246 : TimeChangeUi(rpc_value, base, "pitch", graph_queue, character_queue){};
247 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
248
249private:
250 void updateConfig() override;
251 double pitch_angle_ = 0.;
252};
253
255{
256public:
257 explicit ImageTransmissionAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base,
258 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
259 : TimeChangeUi(rpc_value, base, "image_transmission", graph_queue, character_queue){};
260 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
261
262private:
263 void updateConfig() override;
264 double image_transmission_angle_ = 0.;
265};
266
268{
269public:
270 explicit JointPositionTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
271 std::deque<Graph>* character_queue, std::string name)
272 : TimeChangeUi(rpc_value, base, name, graph_queue, character_queue)
273 {
274 if (rpc_value.hasMember("data"))
275 {
276 XmlRpc::XmlRpcValue data = rpc_value["data"];
277 min_val_ = static_cast<double>(data["min_val"]);
278 max_val_ = static_cast<double>(data["max_val"]);
279 direction_ = static_cast<std::string>(data["direction"]);
280 length_ = static_cast<double>(data["line_length"]);
281 }
282 name_ = name;
283 };
284 void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);
285
286private:
287 void updateConfig() override;
288 std::string name_, direction_;
289 double max_val_, min_val_, current_val_, length_;
290};
291
293{
294public:
295 explicit BulletTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
296 std::deque<Graph>* character_queue)
297 : TimeChangeUi(rpc_value, base, "remaining_bullet", graph_queue, character_queue){};
298 void updateBulletData(const rm_msgs::BulletAllowance& data, const ros::Time& time);
299 void reset();
300
301private:
302 void updateConfig() override;
303 int bullet_allowance_num_17_mm_, bullet_allowance_num_42_mm_, bullet_num_17_mm_{ 0 }, bullet_num_42_mm_{ 0 };
304};
305
307{
308public:
309 explicit TargetDistanceTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
310 std::deque<Graph>* character_queue)
311 : TimeChangeUi(rpc_value, base, "target_distance", graph_queue, character_queue){};
312 void updateTargetDistanceData(const rm_msgs::TrackData::ConstPtr& data);
313
314private:
315 void updateConfig() override;
316 double target_distance_;
317};
318
320{
321public:
322 explicit DroneTowardsTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
323 std::deque<Graph>* character_queue)
324 : TimeChangeGroupUi(rpc_value, base, "drone_towards", graph_queue, character_queue)
325 {
326 if (rpc_value.hasMember("data"))
327 {
328 XmlRpc::XmlRpcValue& data = rpc_value["data"];
329 ori_x_ = static_cast<int>(data["ori_x"]);
330 ori_y_ = static_cast<int>(data["ori_y"]);
331 }
332 else
333 ROS_WARN("DroneTowardsTimeChangeGroupUi config 's member 'data' not defined.");
334
335 graph_vector_.insert(
336 std::pair<std::string, Graph*>(graph_name_ + "_mid", new Graph(rpc_value["config"], base_, id_++)));
337 graph_vector_.insert(
338 std::pair<std::string, Graph*>(graph_name_ + "_left", new Graph(rpc_value["config"], base_, id_++)));
339 graph_vector_.insert(
340 std::pair<std::string, Graph*>(graph_name_ + "_right", new Graph(rpc_value["config"], base_, id_++)));
341 };
342 void updateTowardsData(const geometry_msgs::PoseStampedConstPtr& data);
343
344private:
345 void updateConfig() override;
346 int ori_x_, ori_y_;
347 double angle_;
348 int mid_line_x1_, mid_line_y1_, mid_line_x2_, mid_line_y2_, left_line_x2_, left_line_y2_, right_line_x2_,
349 right_line_y2_;
350};
351
353{
354public:
355 explicit FriendBulletsTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
356 std::deque<Graph>* character_queue)
357 : TimeChangeGroupUi(rpc_value, base, "friend_bullets", graph_queue, character_queue)
358 {
359 graph_vector_.insert(std::pair<std::string, Graph*>("hero", new Graph(rpc_value["config"], base_, id_++)));
360 graph_vector_.insert(std::pair<std::string, Graph*>("standard3", new Graph(rpc_value["config"], base_, id_++)));
361 graph_vector_.insert(std::pair<std::string, Graph*>("standard4", new Graph(rpc_value["config"], base_, id_++)));
362 graph_vector_.insert(std::pair<std::string, Graph*>("standard5", new Graph(rpc_value["config"], base_, id_++)));
363 int ui_start_y = 0;
364 for (auto it = graph_vector_.begin(); it != graph_vector_.end(); ++it)
365 {
366 if (it == graph_vector_.begin())
367 ui_start_y = it->second->getConfig().start_y;
368 else
369 {
370 ui_start_y -= 40;
371 it->second->setStartY(ui_start_y);
372 }
373 }
374 };
375 void updateBulletsData(const rm_referee::BulletNumData& data);
376
377private:
378 void updateConfig() override;
379 int hero_bullets_{ 1 }, standard3_bullets_{ 3 }, standard4_bullets_{ 4 }, standard5_bullets_{ 5 };
380};
381
382} // namespace rm_referee
Definition time_change_ui.h:180
BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:182
Definition data.h:112
Definition time_change_ui.h:293
BulletTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:295
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:85
void updateDartClientCmd(const rm_msgs::DartClientCmd::ConstPtr data, const ros::Time &last_get_data_time)
Definition time_change_ui.cpp:153
DartStatusTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:87
Definition time_change_ui.h:320
DroneTowardsTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:322
Definition time_change_ui.h:57
void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time &time)
Definition time_change_ui.cpp:95
EffortTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:59
Definition time_change_ui.h:353
FriendBulletsTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:355
Definition graph.h:13
Definition ui_base.h:72
Definition time_change_ui.h:255
ImageTransmissionAngleTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:257
Definition time_change_ui.h:268
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:270
Definition time_change_ui.h:133
double end_point_a_angle_
Definition time_change_ui.h:171
double camera_range_
Definition time_change_ui.h:169
LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:135
std::string reference_frame_
Definition time_change_ui.h:168
Definition time_change_ui.h:242
PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:244
Definition time_change_ui.h:71
void updateEngineerUiData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time &last_get_data_time)
Definition time_change_ui.cpp:124
ProgressTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:73
Definition time_change_ui.h:98
RotationTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:100
Definition time_change_ui.h:307
TargetDistanceTimeChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition time_change_ui.h:309
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:101