8#include "std_msgs/String.h"
16 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
17 :
UiBase(rpc_value, base, graph_queue, character_queue)
19 if (graph_name ==
"chassis")
24 virtual void updateConfig(uint8_t main_mode,
bool main_flag, uint8_t sub_mode = 0,
bool sub_flag =
false){};
34 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
35 :
GroupUiBase(rpc_value, base, graph_queue, character_queue)
39 virtual void updateConfig(uint8_t main_mode,
bool main_flag, uint8_t sub_mode = 0,
bool sub_flag =
false){};
52 std::deque<Graph>* character_queue)
53 :
TriggerChangeUi(rpc_value, base,
"chassis", graph_queue, character_queue)
60 if (rpc_value.hasMember(
"mode_change_threshold"))
61 mode_change_threshold_ =
static_cast<double>(rpc_value[
"mode_change_threshold"]);
63 mode_change_threshold_ = 0.7;
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_;
85 std::deque<Graph>* character_queue)
86 :
TriggerChangeUi(rpc_value, base,
"shooter", graph_queue, character_queue)
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_;
104 std::deque<Graph>* character_queue)
105 :
TriggerChangeUi(rpc_value, base,
"gimbal", graph_queue, character_queue)
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_;
123 std::deque<Graph>* character_queue)
124 :
TriggerChangeUi(rpc_value, base,
"target", graph_queue, character_queue)
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_;
146 std::deque<Graph>* character_queue)
147 :
TriggerChangeUi(rpc_value, base,
"target_scale", graph_queue, character_queue)
153 void update()
override;
154 void updateConfig(uint8_t main_mode,
bool main_flag, uint8_t sub_mode = 0,
bool sub_flag =
false)
override;
162 std::deque<Graph>* character_queue)
165 ROS_ASSERT(rpc_value.hasMember(
"points"));
166 XmlRpc::XmlRpcValue config;
168 config[
"type"] =
"line";
170 if (rpc_value[
"graph_config"].hasMember(
"color"))
171 config[
"color"] = rpc_value[
"graph_config"][
"color"];
173 config[
"color"] =
"cyan";
174 if (rpc_value[
"graph_config"].hasMember(
"width"))
175 config[
"width"] = rpc_value[
"graph_config"][
"width"];
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++)
183 if (i != points.size())
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];
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];
199 std::make_pair<std::string, Graph*>(
"graph_" + std::to_string(i),
new Graph(config,
base_,
id_++)));
209 std::deque<Graph>* character_queue)
210 :
TriggerChangeUi(rpc_value, base,
"camera", graph_queue, character_queue)
212 if (rpc_value.hasMember(
"camera_name"))
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"]);
219 ROS_WARN(
"Camera config 's member 'camera_name' not defined.");
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_{};
234 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
235 :
TriggerChangeUi(rpc_value, base, name, graph_queue, character_queue){};
239 void update()
override;
247 std::deque<Graph>* character_queue)
248 :
TriggerChangeUi(rpc_value, base,
"friction_speed", graph_queue, character_queue){};
252 void update()
override;
260 std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
263 if (rpc_value.hasMember(
"data"))
265 XmlRpc::XmlRpcValue& data = rpc_value[
"data"];
266 for (int i = 0; i < static_cast<int>(rpc_value[
"data"].size()); i++)
268 graph_vector_.insert(
269 std::pair<std::string, Graph*>(std::to_string(i), new Graph(data[i][
"config"], base_, id_++)));
273 void updateUiColor(
const std::vector<bool>& data);
276 void update()
override;
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
void setColor(const rm_referee::GraphColor &color)
Definition graph.h:34
void setContent(const std::string &content)
Definition graph.h:38
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
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
@ PINK
Definition protocol.h:158
@ CYAN
Definition protocol.h:159
@ BLUE_ENGINEER
Definition protocol.h:116
@ RED_ENGINEER
Definition protocol.h:106