7#include <tf/transform_listener.h>
13#include <rm_msgs/StatusChangeRequest.h>
22 explicit UiBase(XmlRpc::XmlRpcValue& rpc_value,
Base& base, std::deque<Graph>* graph_queue =
nullptr,
23 std::deque<Graph>* character_queue =
nullptr)
26 if (rpc_value.hasMember(
"config"))
27 if (rpc_value[
"config"].hasMember(
"delay"))
28 delay_ = ros::Duration(
static_cast<double>(rpc_value[
"config"][
"delay"]));
39 virtual void updateManualCmdData(
const rm_msgs::ManualToReferee::ConstPtr data,
const ros::Time& last_get_data_time){};
40 virtual void sendUi(
const ros::Time& time);
45 void sendSerial(
const ros::Time& time,
int data_len);
48 virtual void display(
bool check_repeat =
true);
50 virtual void display(
const ros::Time& time);
51 void display(
const ros::Time& time,
bool state,
bool once =
false);
52 void pack(uint8_t* tx_buffer, uint8_t* data,
int cmd_id,
int len)
const;
67 ros::Duration
delay_ = ros::Duration(0.);
74 explicit GroupUiBase(XmlRpc::XmlRpcValue& rpc_value,
Base& base, std::deque<Graph>* graph_queue =
nullptr,
75 std::deque<Graph>* character_queue =
nullptr)
76 :
UiBase(rpc_value, base, graph_queue, character_queue){};
83 void sendUi(
const ros::Time& time)
override;
88 void display(
bool check_repeat =
true)
override;
89 void display(
const ros::Time& time)
override;
100 explicit FixedUi(XmlRpc::XmlRpcValue& rpc_value,
Base& base, std::deque<Graph>* graph_queue =
nullptr,
101 std::deque<Graph>* character_queue =
nullptr)
102 :
GroupUiBase(rpc_value, base, graph_queue, character_queue)
104 for (
int i = 0; i < static_cast<int>(rpc_value.size()); i++)
106 if (rpc_value[i][
"config"][
"type"] ==
"string")
108 ROS_INFO_STREAM(
"string FixedUi:" << rpc_value[i][
"name"]);
110 std::pair<std::string, Graph*>(rpc_value[i][
"name"],
new Graph(rpc_value[i][
"config"],
base_,
id_++)));
114 std::pair<std::string, Graph*>(rpc_value[i][
"name"],
new Graph(rpc_value[i][
"config"],
base_,
id_++)));
void updateForQueue() override
Definition ui_base.cpp:321
int update_fixed_ui_times
Definition ui_base.h:118
FixedUi(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:100
void erasure() override
Definition ui_base.cpp:82
std::map< std::string, Graph * > character_vector_
Definition ui_base.h:94
void display(bool check_repeat=true) override
Definition ui_base.cpp:200
void updateForQueue() override
Definition ui_base.cpp:91
void add() override
Definition ui_base.cpp:45
void sendDoubleGraph(const ros::Time &time, Graph *graph0, Graph *graph1)
Definition ui_base.cpp:263
std::map< std::string, Graph * > graph_vector_
Definition ui_base.h:93
void displayTwice(bool check_repeat=true) override
Definition ui_base.cpp:222
void sendSevenGraph(const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4, Graph *graph5, Graph *graph6)
Definition ui_base.cpp:299
void sendUi(const ros::Time &time) override
Definition ui_base.cpp:252
void addForQueue(int add_times=1) override
Definition ui_base.cpp:54
void update() override
Definition ui_base.cpp:73
void sendFiveGraph(const ros::Time &time, Graph *graph0, Graph *graph1, Graph *graph2, Graph *graph3, Graph *graph4)
Definition ui_base.cpp:279
GroupUiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:74
virtual void add()
Definition ui_base.cpp:10
std::deque< Graph > * graph_queue_
Definition ui_base.h:61
uint8_t tx_buffer_[127]
Definition ui_base.h:54
virtual void display(bool check_repeat=true)
Definition ui_base.cpp:105
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time &last_get_data_time)
Definition ui_base.h:39
Graph * graph_
Definition ui_base.h:59
const int k_frame_length_
Definition ui_base.h:68
tf2_ros::TransformListener tf_listener_
Definition ui_base.h:64
void pack(uint8_t *tx_buffer, uint8_t *data, int cmd_id, int len) const
Definition ui_base.cpp:339
void sendSerial(const ros::Time &time, int data_len)
Definition ui_base.cpp:352
ros::Time last_send_
Definition ui_base.h:66
ros::Duration delay_
Definition ui_base.h:67
void sendSingleGraph(const ros::Time &time, Graph *graph)
Definition ui_base.cpp:185
std::deque< Graph > * character_queue_
Definition ui_base.h:62
void clearTxBuffer()
Definition ui_base.cpp:366
virtual void sendUi(const ros::Time &time)
Definition ui_base.cpp:151
virtual void erasure()
Definition ui_base.cpp:32
virtual void update()
Definition ui_base.cpp:26
const int k_header_length_
Definition ui_base.h:68
void sendCharacter(const ros::Time &time, Graph *graph)
Definition ui_base.cpp:162
const int k_cmd_id_length_
Definition ui_base.h:68
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data)
Definition ui_base.h:38
tf2_ros::Buffer tf_buffer_
Definition ui_base.h:63
virtual void updateForQueue()
Definition ui_base.cpp:38
static int id_
Definition ui_base.h:60
virtual void addForQueue(int add_times=1)
Definition ui_base.cpp:16
const int k_tail_length_
Definition ui_base.h:68
virtual void displayTwice(bool check_repeat=true)
Definition ui_base.cpp:114
int tx_len_
Definition ui_base.h:55
Base & base_
Definition ui_base.h:58
UiBase(XmlRpc::XmlRpcValue &rpc_value, Base &base, std::deque< Graph > *graph_queue=nullptr, std::deque< Graph > *character_queue=nullptr)
Definition ui_base.h:22