rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
trigger_change_ui.h
Go to the documentation of this file.
1//
2// Created by llljjjqqq on 22-11-4.
3//
4#pragma once
5
8#include "std_msgs/String.h"
9
10namespace rm_referee
11{
12class TriggerChangeUi : public UiBase
13{
14public:
15 explicit TriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
16 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
17 : UiBase(rpc_value, base, graph_queue, character_queue)
18 {
19 if (graph_name == "chassis")
20 graph_ = new Graph(rpc_value["config"], base_, 1);
21 else
22 graph_ = new Graph(rpc_value["config"], base_, id_++);
23 };
24 virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
25 void updateForQueue() override;
26 void updateForQueue(bool check_repeat);
27 void updateTwiceForQueue(bool check_repeat = true);
28};
29
31{
32public:
33 explicit TriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
34 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
35 : GroupUiBase(rpc_value, base, graph_queue, character_queue)
36 {
37 graph_name_ = graph_name;
38 };
39 virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
40 void updateForQueue() override;
41 void updateForQueue(bool check_repeat);
42 void updateTwiceForQueue(bool check_repeat = true);
43
44protected:
45 std::string graph_name_;
46};
47
49{
50public:
51 explicit ChassisTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
52 std::deque<Graph>* character_queue)
53 : TriggerChangeUi(rpc_value, base, "chassis", graph_queue, character_queue)
54 {
56 graph_->setContent("raw");
57 else
58 graph_->setContent("follow");
59
60 if (rpc_value.hasMember("mode_change_threshold"))
61 mode_change_threshold_ = static_cast<double>(rpc_value["mode_change_threshold"]);
62 else
63 mode_change_threshold_ = 0.7;
64 }
65 void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr& data);
66 void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;
67 void updateDbusData(const rm_msgs::DbusData::ConstPtr& data);
69 void checkModeChange();
70
71private:
72 void update() override;
73 void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false,
74 bool extra_flag = false);
75 void displayInCapacity();
76 std::string getChassisState(uint8_t mode);
77 uint8_t chassis_mode_, power_limit_state_, s_l_, s_r_, key_ctrl_, key_shift_, key_b_;
78 double mode_change_threshold_;
79};
80
82{
83public:
84 explicit ShooterTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
85 std::deque<Graph>* character_queue)
86 : TriggerChangeUi(rpc_value, base, "shooter", graph_queue, character_queue)
87 {
88 graph_->setContent("0");
89 }
90 void updateShootStateData(const rm_msgs::ShootState::ConstPtr& data);
91 void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;
92
93private:
94 void update() override;
95 void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false) override;
96 std::string getShooterState(uint8_t mode);
97 uint8_t shooter_mode_, shoot_frequency_;
98};
99
101{
102public:
103 explicit GimbalTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
104 std::deque<Graph>* character_queue)
105 : TriggerChangeUi(rpc_value, base, "gimbal", graph_queue, character_queue)
106 {
107 graph_->setContent("0");
108 }
109 void updateGimbalCmdData(const rm_msgs::GimbalCmd ::ConstPtr& data);
110 void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;
111
112private:
113 void update() override;
114 void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false) override;
115 std::string getGimbalState(uint8_t mode);
116 uint8_t gimbal_mode_, gimbal_eject_;
117};
118
120{
121public:
122 explicit TargetTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
123 std::deque<Graph>* character_queue)
124 : TriggerChangeUi(rpc_value, base, "target", graph_queue, character_queue)
125 {
126 graph_->setContent("armor");
127 if (base_.robot_color_ == "red")
129 else
131 }
132 void updateShootStateData(const rm_msgs::ShootState::ConstPtr& data);
133 void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;
134
135private:
136 void update() override;
137 void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false) override;
138 std::string getTargetState(uint8_t target, uint8_t armor_target);
139 uint8_t det_target_, shoot_frequency_, det_armor_target_, det_color_, gimbal_eject_;
140};
141
143{
144public:
145 explicit TargetViewAngleTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
146 std::deque<Graph>* character_queue)
147 : TriggerChangeUi(rpc_value, base, "target_scale", graph_queue, character_queue)
148 {
149 }
150 void updateTrackID(int id);
151
152private:
153 void update() override;
154 void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false) override;
155 int track_id_;
156};
157
159{
160public:
161 explicit PolygonTriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
162 std::deque<Graph>* character_queue)
163 : TriggerChangeGroupUi(rpc_value, base, "Polygon", graph_queue, character_queue)
164 {
165 ROS_ASSERT(rpc_value.hasMember("points"));
166 XmlRpc::XmlRpcValue config;
167
168 config["type"] = "line";
169
170 if (rpc_value["graph_config"].hasMember("color"))
171 config["color"] = rpc_value["graph_config"]["color"];
172 else
173 config["color"] = "cyan";
174 if (rpc_value["graph_config"].hasMember("width"))
175 config["width"] = rpc_value["graph_config"]["width"];
176 else
177 config["width"] = 2;
178 XmlRpc::XmlRpcValue points = rpc_value["points"];
179 config["start_position"].setSize(2);
180 config["end_position"].setSize(2);
181 for (int i = 1; i <= points.size(); i++)
182 {
183 if (i != points.size())
184 {
185 config["start_position"][0] = points[i - 1][0];
186 config["start_position"][1] = points[i - 1][1];
187 config["end_position"][0] = points[i][0];
188 config["end_position"][1] = points[i][1];
189 }
190 else
191 {
192 // Connect first and last point
193 config["start_position"][0] = points[i - 1][0];
194 config["start_position"][1] = points[i - 1][1];
195 config["end_position"][0] = points[0][0];
196 config["end_position"][1] = points[0][1];
197 }
198 graph_vector_.insert(
199 std::make_pair<std::string, Graph*>("graph_" + std::to_string(i), new Graph(config, base_, id_++)));
200 }
201 }
202 void update() override;
203};
204
206{
207public:
208 explicit CameraTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
209 std::deque<Graph>* character_queue)
210 : TriggerChangeUi(rpc_value, base, "camera", graph_queue, character_queue)
211 {
212 if (rpc_value.hasMember("camera_name"))
213 {
214 XmlRpc::XmlRpcValue& data = rpc_value["camera_name"];
215 camera1_name_ = static_cast<std::string>(data["camera1_name"]);
216 camera2_name_ = static_cast<std::string>(data["camera2_name"]);
217 }
218 else
219 ROS_WARN("Camera config 's member 'camera_name' not defined.");
220 graph_->setContent("0");
221 }
222 void updateCameraName(const std_msgs::StringConstPtr& data);
223
224private:
225 void update() override;
226 void updateConfig(uint8_t main_mode = 0, bool main_flag = false, uint8_t sub_mode = 0, bool sub_flag = false) override;
227 std::string current_camera_{}, camera1_name_{}, camera2_name_{};
228};
229
231{
232public:
233 explicit StringTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& name,
234 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
235 : TriggerChangeUi(rpc_value, base, name, graph_queue, character_queue){};
236 void updateStringUiData(const std::string& data);
237
238private:
239 void update() override;
240 std::string data_;
241};
242
244{
245public:
246 explicit FrictionSpeedTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
247 std::deque<Graph>* character_queue)
248 : TriggerChangeUi(rpc_value, base, "friction_speed", graph_queue, character_queue){};
249 void updateFrictionSpeedUiData(const rm_msgs::ShootCmdConstPtr& data);
250
251private:
252 void update() override;
253 double wheel_speed_;
254};
255
257{
258public:
259 explicit VisualizeStateTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& name,
260 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
261 : TriggerChangeGroupUi(rpc_value, base, name, graph_queue, character_queue)
262 {
263 if (rpc_value.hasMember("data"))
264 {
265 XmlRpc::XmlRpcValue& data = rpc_value["data"];
266 for (int i = 0; i < static_cast<int>(rpc_value["data"].size()); i++)
267 {
268 graph_vector_.insert(
269 std::pair<std::string, Graph*>(std::to_string(i), new Graph(data[i]["config"], base_, id_++)));
270 }
271 }
272 };
273 void updateUiColor(const std::vector<bool>& data);
274
275private:
276 void update() override;
277};
278
279} // namespace rm_referee
Definition data.h:112
std::string robot_color_
Definition data.h:119
int robot_id_
Definition data.h:117
Definition trigger_change_ui.h:206
void updateCameraName(const std_msgs::StringConstPtr &data)
Definition trigger_change_ui.cpp:406
CameraTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:208
Definition trigger_change_ui.h:49
void updateDbusData(const rm_msgs::DbusData::ConstPtr &data)
Definition trigger_change_ui.cpp:216
void checkModeChange()
Definition trigger_change_ui.cpp:107
ChassisTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:51
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr &data)
Definition trigger_change_ui.cpp:205
void updateCapacityResetStatus()
Definition trigger_change_ui.cpp:225
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override
Definition trigger_change_ui.cpp:211
Definition trigger_change_ui.h:244
FrictionSpeedTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:246
void updateFrictionSpeedUiData(const rm_msgs::ShootCmdConstPtr &data)
Definition trigger_change_ui.cpp:444
Definition trigger_change_ui.h:101
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override
Definition trigger_change_ui.cpp:308
void updateGimbalCmdData(const rm_msgs::GimbalCmd ::ConstPtr &data)
Definition trigger_change_ui.cpp:302
GimbalTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:103
Definition graph.h:13
void setColor(const rm_referee::GraphColor &color)
Definition graph.h:34
void setContent(const std::string &content)
Definition graph.h:38
Definition ui_base.h:72
std::map< std::string, Graph * > graph_vector_
Definition ui_base.h:93
Definition trigger_change_ui.h:159
PolygonTriggerChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:161
void update() override
Definition trigger_change_ui.cpp:399
Definition trigger_change_ui.h:82
ShooterTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:84
void updateShootStateData(const rm_msgs::ShootState::ConstPtr &data)
Definition trigger_change_ui.cpp:262
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override
Definition trigger_change_ui.cpp:268
Definition trigger_change_ui.h:231
void updateStringUiData(const std::string &data)
Definition trigger_change_ui.cpp:430
StringTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:233
Definition trigger_change_ui.h:120
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override
Definition trigger_change_ui.cpp:364
void updateShootStateData(const rm_msgs::ShootState::ConstPtr &data)
Definition trigger_change_ui.cpp:373
TargetTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:122
Definition trigger_change_ui.h:143
void updateTrackID(int id)
Definition trigger_change_ui.cpp:393
TargetViewAngleTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:145
Definition trigger_change_ui.h:31
TriggerChangeGroupUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &graph_name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:33
void updateTwiceForQueue(bool check_repeat=true)
Definition trigger_change_ui.cpp:60
void updateForQueue() override
Definition trigger_change_ui.cpp:33
std::string graph_name_
Definition trigger_change_ui.h:45
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode=0, bool sub_flag=false)
Definition trigger_change_ui.h:39
Definition trigger_change_ui.h:13
TriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &graph_name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:15
void updateTwiceForQueue(bool check_repeat=true)
Definition trigger_change_ui.cpp:23
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode=0, bool sub_flag=false)
Definition trigger_change_ui.h:24
void updateForQueue() override
Definition trigger_change_ui.cpp:9
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 trigger_change_ui.h:257
VisualizeStateTriggerChangeUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, const std::string &name, std::deque< Graph > *graph_queue, std::deque< Graph > *character_queue)
Definition trigger_change_ui.h:259
Definition data.h:101
@ PINK
Definition protocol.h:158
@ CYAN
Definition protocol.h:159
@ BLUE_ENGINEER
Definition protocol.h:116
@ RED_ENGINEER
Definition protocol.h:106