src
ui
flash_ui.cpp
Go to the documentation of this file.
1
//
2
// Created by llljjjqqq on 22-11-4.
3
//
4
5
#include "
rm_referee/ui/flash_ui.h
"
6
7
namespace
rm_referee
8
{
9
void
FlashUi::updateFlashUiForQueue
(
const
ros::Time
& time,
bool
state,
bool
once)
10
{
11
if
(once)
12
{
13
// ROS_INFO("test");
14
if
(state)
15
graph_
->
setOperation
(
rm_referee::GraphOperation::ADD
);
16
else
17
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
18
}
19
else
if
(time -
last_send_
>
delay_
)
20
{
21
// ROS_INFO("%f %.3f", last_send_.toSec(), delay_.toSec());
22
if
(state)
23
graph_
->
setOperation
(
rm_referee::GraphOperation::ADD
);
24
else
25
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
26
// graph_->setOperation(graph_->getOperation() == rm_referee::GraphOperation::ADD ?
27
// rm_referee::GraphOperation::DELETE :
28
// rm_referee::GraphOperation::ADD);
29
// ROS_INFO("delay");
30
}
31
if
(
graph_
->
isRepeated
())
32
return
;
33
graph_
->
updateLastConfig
();
34
last_send_
= time;
35
UiBase::updateForQueue
();
36
}
37
38
void
FlashGroupUi::updateFlashUiForQueue
(
const
ros::Time
& time,
bool
state,
bool
once)
39
{
40
if
(once)
41
{
42
if
(state)
43
{
44
for
(
auto
graph :
graph_vector_
)
45
graph.second->setOperation(
rm_referee::GraphOperation::ADD
);
46
for
(
auto
character :
character_vector_
)
47
character.second->setOperation(
rm_referee::GraphOperation::ADD
);
48
}
49
else
50
{
51
for
(
auto
graph :
graph_vector_
)
52
graph.second->setOperation(
rm_referee::GraphOperation::DELETE
);
53
for
(
auto
character :
character_vector_
)
54
character.second->setOperation(
rm_referee::GraphOperation::DELETE
);
55
}
56
}
57
else
if
(time -
last_send_
>
delay_
)
58
{
59
ROS_INFO
(
"%f %.3f"
,
last_send_
.
toSec
(),
delay_
.
toSec
());
60
if
(state)
61
{
62
for
(
auto
graph :
graph_vector_
)
63
graph.second->setOperation(
rm_referee::GraphOperation::ADD
);
64
for
(
auto
character :
character_vector_
)
65
character.second->setOperation(
rm_referee::GraphOperation::ADD
);
66
}
67
else
68
{
69
for
(
auto
graph :
graph_vector_
)
70
graph.second->setOperation(
rm_referee::GraphOperation::DELETE
);
71
for
(
auto
character :
character_vector_
)
72
character.second->setOperation(
rm_referee::GraphOperation::DELETE
);
73
}
74
}
75
76
bool
is_repeat =
true
;
77
for
(
auto
it :
graph_vector_
)
78
if
(!it.second->isRepeated())
79
is_repeat =
false
;
80
for
(
auto
it :
character_vector_
)
81
if
(!it.second->isRepeated())
82
is_repeat =
false
;
83
if
(is_repeat)
84
return
;
85
86
for
(
auto
it :
graph_vector_
)
87
it.second->updateLastConfig();
88
for
(
auto
it :
character_vector_
)
89
it.second->updateLastConfig();
90
91
last_send_
= time;
92
for
(
auto
it :
character_vector_
)
93
character_queue_
->push_back(*it.second);
94
for
(
auto
it :
graph_vector_
)
95
graph_queue_
->push_back(*it.second);
96
}
97
98
void
FlashGroupUi::updateFlashUiForQueue
(
const
ros::Time
& time,
bool
state,
bool
once,
Graph
* graph)
99
{
100
if
(once)
101
{
102
if
(state)
103
graph->
setOperation
(
rm_referee::GraphOperation::ADD
);
104
else
105
graph->
setOperation
(
rm_referee::GraphOperation::DELETE
);
106
}
107
else
if
(time -
last_send_
>
delay_
)
108
{
109
ROS_INFO
(
"%f %.3f"
,
last_send_
.
toSec
(),
delay_
.
toSec
());
110
if
(state)
111
graph->
setOperation
(
rm_referee::GraphOperation::ADD
);
112
else
113
graph->
setOperation
(
rm_referee::GraphOperation::DELETE
);
114
}
115
if
(graph->
isRepeated
())
116
return
;
117
graph->
updateLastConfig
();
118
last_send_
= time;
119
if
(graph->
isString
())
120
character_queue_
->push_back(*graph);
121
else
122
graph_queue_
->push_back(*graph);
123
}
124
125
void
CustomizeDisplayFlashUi::updateCmdData
(
const
uint32_t& data)
126
{
127
symbol_
= data;
128
display
(
ros::Time::now
());
129
}
130
131
void
CustomizeDisplayFlashUi::display
(
const
ros::Time
& time)
132
{
133
for
(
auto
graph :
graph_vector_
)
134
{
135
bool
state =
false
;
136
if
(std::to_string(
static_cast<
int
>
(
symbol_
)) == graph.first)
137
state =
true
;
138
FlashGroupUi::updateFlashUiForQueue
(time, state,
true
, graph.second);
139
}
140
}
141
142
void
CoverFlashUi::display
(
const
ros::Time
& time)
143
{
144
if
(!
cover_state_
)
145
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
146
FlashUi::updateFlashUiForQueue
(time,
cover_state_
,
true
);
147
}
148
149
void
CoverFlashUi::updateManualCmdData
(
const
rm_msgs::ManualToReferee::ConstPtr data,
150
const
ros::Time
& last_get_data_time)
151
{
152
cover_state_
= data->cover_state;
153
display
(last_get_data_time);
154
}
155
156
void
SpinFlashUi::display
(
const
ros::Time
& time)
157
{
158
if
(
chassis_mode_
!= rm_msgs::ChassisCmd::RAW)
159
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
160
FlashUi::updateFlashUiForQueue
(time,
chassis_mode_
!= rm_msgs::ChassisCmd::RAW,
true
);
161
}
162
163
void
SpinFlashUi::updateChassisCmdData
(
const
rm_msgs::ChassisCmd::ConstPtr data,
const
ros::Time
& last_get_data_time)
164
{
165
chassis_mode_
= data->mode;
166
display
(last_get_data_time);
167
}
168
169
void
DeployFlashUi::display
(
const
ros::Time
& time)
170
{
171
if
(!(
chassis_mode_
== rm_msgs::ChassisCmd::RAW &&
angular_z_
== 0.0))
172
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
173
FlashUi::updateFlashUiForQueue
(time, (
chassis_mode_
== rm_msgs::ChassisCmd::RAW &&
angular_z_
== 0.0),
false
);
174
}
175
176
void
DeployFlashUi::updateChassisCmdData
(
const
rm_msgs::ChassisCmd::ConstPtr& data,
const
ros::Time
& last_get_data_time)
177
{
178
chassis_mode_
= data->mode;
179
display
(last_get_data_time);
180
}
181
182
void
DeployFlashUi::updateChassisVelData
(
const
geometry_msgs::Twist::ConstPtr& data)
183
{
184
angular_z_
= data->angular.z;
185
}
186
187
void
HeroHitFlashUi::updateHittingConfig
(
const
rm_msgs::GameRobotHp& msg)
188
{
189
if
(
base_
.
robot_id_
> 100)
190
{
191
hitted_
=
192
(
last_hp_msg_
.red_outpost_hp - msg.red_outpost_hp > 190 ||
last_hp_msg_
.red_base_hp - msg.red_base_hp > 190);
193
}
194
else
195
{
196
hitted_
= (
last_hp_msg_
.blue_outpost_hp - msg.blue_outpost_hp > 190 ||
197
last_hp_msg_
.blue_base_hp - msg.blue_base_hp > 190);
198
}
199
last_hp_msg_
= msg;
200
display
(
ros::Time::now
());
201
}
202
203
void
HeroHitFlashUi::display
(
const
ros::Time
& time)
204
{
205
if
(
hitted_
)
206
FlashGroupUi::updateFlashUiForQueue
(time,
true
,
true
);
207
else
208
FlashGroupUi::updateFlashUiForQueue
(time,
false
,
false
);
209
}
210
211
void
ExceedBulletSpeedFlashUi::display
(
const
ros::Time
& time)
212
{
213
if
(
shoot_data_
.bullet_speed <= 30)
214
graph_
->
setOperation
(
rm_referee::GraphOperation::DELETE
);
215
FlashUi::updateFlashUiForQueue
(time,
shoot_data_
.bullet_speed > 30,
true
);
216
}
217
218
void
ExceedBulletSpeedFlashUi::updateShootData
(
const
rm_msgs::ShootData& msg)
219
{
220
shoot_data_
= msg;
221
}
222
223
void
BurstFlashUi::display
(
const
ros::Time
& time)
224
{
225
ros::Time
now =
ros::Time::now
();
226
if
(now -
start_burst_time_
<
ros::Duration
(20))
227
{
228
graph_
->
setColor
(
rm_referee::GraphColor::PURPLE
);
229
FlashUi::updateFlashUiForQueue
(time,
true
,
false
);
230
}
231
else
232
FlashUi::updateFlashUiForQueue
(time,
false
,
false
);
233
}
234
235
void
BurstFlashUi::updateBurstTimeData
(
const
rm_msgs::ManualToReferee::ConstPtr& data)
236
{
237
start_burst_time_
= data->start_burst_time;
238
display
(
ros::Time::now
());
239
}
240
}
// namespace rm_referee
241
// namespace rm_referee
rm_referee::ExceedBulletSpeedFlashUi::updateShootData
void updateShootData(const rm_msgs::ShootData &msg)
Definition:
flash_ui.cpp:218
rm_referee::SpinFlashUi::updateChassisCmdData
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr data, const ros::Time &last_get_data_time)
Definition:
flash_ui.cpp:163
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::DeployFlashUi::chassis_mode_
uint8_t chassis_mode_
Definition:
flash_ui.h:105
rm_referee
Definition:
data.h:100
rm_referee::ExceedBulletSpeedFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:211
rm_referee::CoverFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:142
rm_referee::Graph::isString
bool isString()
Definition:
graph.h:97
rm_referee::PURPLE
@ PURPLE
Definition:
protocol.h:157
rm_referee::CoverFlashUi::cover_state_
uint8_t cover_state_
Definition:
flash_ui.h:78
rm_referee::FlashUi::updateFlashUiForQueue
void updateFlashUiForQueue(const ros::Time &time, bool state, bool once)
Definition:
flash_ui.cpp:9
rm_referee::HeroHitFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:203
TimeBase< Time, Duration >::toSec
double toSec() const
rm_referee::DeployFlashUi::angular_z_
double angular_z_
Definition:
flash_ui.h:106
rm_referee::BurstFlashUi::start_burst_time_
ros::Time start_burst_time_
Definition:
flash_ui.h:171
rm_referee::UiBase::character_queue_
std::deque< Graph > * character_queue_
Definition:
ui_base.h:62
rm_referee::HeroHitFlashUi::last_hp_msg_
rm_msgs::GameRobotHp last_hp_msg_
Definition:
flash_ui.h:141
rm_referee::CustomizeDisplayFlashUi::updateCmdData
void updateCmdData(const uint32_t &data)
Definition:
flash_ui.cpp:125
rm_referee::UiBase::delay_
ros::Duration delay_
Definition:
ui_base.h:67
rm_referee::FlashGroupUi::updateFlashUiForQueue
void updateFlashUiForQueue(const ros::Time &time, bool state, bool once)
Definition:
flash_ui.cpp:38
rm_referee::HeroHitFlashUi::updateHittingConfig
void updateHittingConfig(const rm_msgs::GameRobotHp &msg)
Definition:
flash_ui.cpp:187
rm_referee::BurstFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:223
flash_ui.h
rm_referee::DeployFlashUi::updateChassisVelData
void updateChassisVelData(const geometry_msgs::Twist::ConstPtr &data)
Definition:
flash_ui.cpp:182
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::UiBase::last_send_
ros::Time last_send_
Definition:
ui_base.h:66
rm_referee::Graph::setColor
void setColor(const rm_referee::GraphColor &color)
Definition:
graph.h:34
rm_referee::UiBase::base_
Base & base_
Definition:
ui_base.h:58
rm_referee::SpinFlashUi::chassis_mode_
uint8_t chassis_mode_
Definition:
flash_ui.h:91
rm_referee::ExceedBulletSpeedFlashUi::shoot_data_
rm_msgs::ShootData shoot_data_
Definition:
flash_ui.h:156
rm_referee::Graph::setOperation
void setOperation(const rm_referee::GraphOperation &operation)
Definition:
graph.h:17
rm_referee::DELETE
@ DELETE
Definition:
protocol.h:148
rm_referee::Graph::updateLastConfig
void updateLastConfig()
Definition:
graph.h:101
rm_referee::SpinFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:156
rm_referee::DeployFlashUi::updateChassisCmdData
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr &data, const ros::Time &last_get_data_time)
Definition:
flash_ui.cpp:176
ros::Time
rm_referee::UiBase::graph_queue_
std::deque< Graph > * graph_queue_
Definition:
ui_base.h:61
rm_referee::CoverFlashUi::updateManualCmdData
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time &last_get_data_time) override
Definition:
flash_ui.cpp:149
rm_referee::CustomizeDisplayFlashUi::symbol_
uint32_t symbol_
Definition:
flash_ui.h:64
rm_referee::BurstFlashUi::updateBurstTimeData
void updateBurstTimeData(const rm_msgs::ManualToReferee::ConstPtr &data)
Definition:
flash_ui.cpp:235
rm_referee::CustomizeDisplayFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:131
DurationBase< Duration >::toSec
double toSec() const
ROS_INFO
#define ROS_INFO(...)
rm_referee::UiBase::graph_
Graph * graph_
Definition:
ui_base.h:59
rm_referee::HeroHitFlashUi::hitted_
bool hitted_
Definition:
flash_ui.h:140
ros::Duration
rm_referee::DeployFlashUi::display
void display(const ros::Time &time) override
Definition:
flash_ui.cpp:169
rm_referee::Graph
Definition:
graph.h:12
ros::Time::now
static Time now()
rm_referee::ADD
@ ADD
Definition:
protocol.h:146
rm_referee
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:49