Skip to content

Commit

Permalink
Merge pull request #202 from GuraMumei/modify-ui-sender
Browse files Browse the repository at this point in the history
Modify UI sender
  • Loading branch information
d0h0s authored Jan 29, 2024
2 parents f0418ac + 5e62fa5 commit 892455f
Show file tree
Hide file tree
Showing 13 changed files with 431 additions and 211 deletions.
14 changes: 10 additions & 4 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,9 @@ class RefereeBase
virtual void sentryDeviateCallback(const rm_msgs::SentryDeviateConstPtr& data);
virtual void sendCurrentSentryCallback(const rm_msgs::CurrentSentryPosDataConstPtr& data);

// send graph_type ui
void sendGraphQueueCallback();
// send ui
void sendSerialDataCallback();
void sendQueue();

ros::Subscriber joint_state_sub_;
ros::Subscriber actuator_state_sub_;
Expand Down Expand Up @@ -101,12 +102,17 @@ class RefereeBase
SpinFlashUi* spin_flash_ui_{};

GroupUiBase* graph_queue_sender_{};
std::vector<Graph> graph_queue_;
std::deque<Graph> graph_queue_;
std::deque<Graph> character_queue_;

rm_referee::ClientMapReceiveData radar_receive_data_;
rm_referee::MapSentryData map_sentry_data_;
ros::Time interactive_data_last_send_;
bool send_radar_receive_data_ = false, send_map_sentry_data_ = false;
UiBase* interactive_data_sender_{};

Base& base_;
ros::Timer add_ui_timer_, send_graph_ui_timer_;
ros::Timer add_ui_timer_, send_serial_data_timer_;
int add_ui_times_, add_ui_max_times_, add_ui_frequency_;
double send_ui_queue_delay_;
bool add_ui_flag_ = false, is_adding_ = false;
Expand Down
16 changes: 10 additions & 6 deletions rm_referee/include/rm_referee/ui/flash_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,32 +12,36 @@ class FlashUi : public UiBase
{
public:
explicit FlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
std::vector<Graph>* graph_queue)
: UiBase(rpc_value, base, graph_queue)
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: UiBase(rpc_value, base, graph_queue, character_queue)
{
graph_ = new Graph(rpc_value["config"], base_, id_++);
}
virtual void display(const ros::Time& time){};
virtual void updateConfig(){};
void updateFlashUiForQueue(const ros::Time& time, bool state, bool once);
};

class CoverFlashUi : public FlashUi
{
public:
explicit CoverFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: FlashUi(rpc_value, base, "cover", graph_queue){};
explicit CoverFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashUi(rpc_value, base, "cover", graph_queue, character_queue){};
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time& last_get_data_time) override;

private:
void display(const ros::Time& time) override;

uint8_t cover_state_;
};

class SpinFlashUi : public FlashUi
{
public:
explicit SpinFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: FlashUi(rpc_value, base, "spin", graph_queue){};
explicit SpinFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashUi(rpc_value, base, "spin", graph_queue, character_queue){};
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr data, const ros::Time& last_get_data_time);

private:
Expand Down
8 changes: 6 additions & 2 deletions rm_referee/include/rm_referee/ui/graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ class Graph
void setContent(const std::string& content)
{
content_ = content;
if (!title_.empty() || !content_.empty())
config_.end_angle = static_cast<int>((title_ + content_).size());
}
void setEndX(int end_x)
{
Expand Down Expand Up @@ -69,10 +71,12 @@ class Graph
{
return config_ == last_config_ && title_ == last_title_ && content_ == last_content_;
}
bool isString()
{
return config_.graphic_type == rm_referee::GraphType::STRING;
}
void updateLastConfig()
{
if (!title_.empty() && !content_.empty())
config_.end_angle = static_cast<int>((title_ + content_).size());
last_content_ = content_;
last_title_ = title_;
last_config_ = config_;
Expand Down
59 changes: 33 additions & 26 deletions rm_referee/include/rm_referee/ui/time_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,27 +12,27 @@ class TimeChangeUi : public UiBase
{
public:
explicit TimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
std::vector<Graph>* graph_queue)
: UiBase(rpc_value, base, graph_queue)
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: UiBase(rpc_value, base, graph_queue, character_queue)
{
graph_ = new Graph(rpc_value["config"], base_, id_++);
}
void update() override;
void updateForQueue();
void updateForQueue() override;
virtual void updateConfig(){};
};

class TimeChangeGroupUi : public GroupUiBase
{
public:
explicit TimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
std::vector<Graph>* graph_queue)
: GroupUiBase(rpc_value, base, graph_queue)
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: GroupUiBase(rpc_value, base, graph_queue, character_queue)
{
graph_name_ = graph_name;
}
void update() override;
void updateForQueue();
void updateForQueue() override;
virtual void updateConfig(){};

protected:
Expand All @@ -42,8 +42,9 @@ class TimeChangeGroupUi : public GroupUiBase
class CapacitorTimeChangeUi : public TimeChangeUi
{
public:
explicit CapacitorTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "capacitor", graph_queue){};
explicit CapacitorTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "capacitor", graph_queue, character_queue){};
void add() override;
void updateRemainCharge(const double remain_charge, const ros::Time& time);

Expand All @@ -55,8 +56,9 @@ class CapacitorTimeChangeUi : public TimeChangeUi
class EffortTimeChangeUi : public TimeChangeUi
{
public:
explicit EffortTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "effort", graph_queue){};
explicit EffortTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "effort", graph_queue, character_queue){};
void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);

private:
Expand All @@ -68,8 +70,9 @@ class EffortTimeChangeUi : public TimeChangeUi
class ProgressTimeChangeUi : public TimeChangeUi
{
public:
explicit ProgressTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "progress", graph_queue){};
explicit ProgressTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "progress", graph_queue, character_queue){};
void updateEngineerUiData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time& last_get_data_time);

private:
Expand All @@ -81,8 +84,9 @@ class ProgressTimeChangeUi : public TimeChangeUi
class DartStatusTimeChangeUi : public TimeChangeUi
{
public:
explicit DartStatusTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "dart", graph_queue){};
explicit DartStatusTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "dart", graph_queue, character_queue){};
void updateDartClientCmd(const rm_msgs::DartClientCmd::ConstPtr data, const ros::Time& last_get_data_time);

private:
Expand All @@ -93,8 +97,9 @@ class DartStatusTimeChangeUi : public TimeChangeUi
class RotationTimeChangeUi : public TimeChangeUi
{
public:
explicit RotationTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "rotation", graph_queue)
explicit RotationTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "rotation", graph_queue, character_queue)
{
if (rpc_value.hasMember("data"))
{
Expand Down Expand Up @@ -125,8 +130,9 @@ class RotationTimeChangeUi : public TimeChangeUi
class LaneLineTimeChangeGroupUi : public TimeChangeGroupUi
{
public:
explicit LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeGroupUi(rpc_value, base, "lane_line", graph_queue)
explicit LaneLineTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeGroupUi(rpc_value, base, "lane_line", graph_queue, character_queue)
{
if (rpc_value.hasMember("data"))
{
Expand Down Expand Up @@ -171,8 +177,9 @@ class LaneLineTimeChangeGroupUi : public TimeChangeGroupUi
class BalancePitchTimeChangeGroupUi : public TimeChangeGroupUi
{
public:
explicit BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeGroupUi(rpc_value, base, "balance_pitch", graph_queue)
explicit BalancePitchTimeChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeGroupUi(rpc_value, base, "balance_pitch", graph_queue, character_queue)
{
XmlRpc::XmlRpcValue config;

Expand Down Expand Up @@ -232,9 +239,9 @@ class BalancePitchTimeChangeGroupUi : public TimeChangeGroupUi
class PitchAngleTimeChangeUi : public TimeChangeUi
{
public:
explicit PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TimeChangeUi(rpc_value, base, "pitch", graph_queue){};
void update() override;
explicit PitchAngleTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "pitch", graph_queue, character_queue){};
void updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time);

private:
Expand All @@ -245,9 +252,9 @@ class PitchAngleTimeChangeUi : public TimeChangeUi
class JointPositionTimeChangeUi : public TimeChangeUi
{
public:
explicit JointPositionTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue,
std::string name)
: TimeChangeUi(rpc_value, base, name, graph_queue)
explicit JointPositionTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue, std::string name)
: TimeChangeUi(rpc_value, base, name, graph_queue, character_queue)
{
if (rpc_value.hasMember("data"))
{
Expand Down
70 changes: 49 additions & 21 deletions rm_referee/include/rm_referee/ui/trigger_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,22 +13,44 @@ class TriggerChangeUi : public UiBase
{
public:
explicit TriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
std::vector<Graph>* graph_queue)
: UiBase(rpc_value, base, graph_queue)
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: UiBase(rpc_value, base, graph_queue, character_queue)
{
if (graph_name == "chassis")
graph_ = new Graph(rpc_value["config"], base_, 1);
else
graph_ = new Graph(rpc_value["config"], base_, id_++);
};
virtual void setContent(const std::string& content);
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
void updateForQueue() override;
void updateForQueue(bool check_repeat);
void updateTwiceForQueue(bool check_repeat = true);
};

class TriggerChangeGroupUi : public GroupUiBase
{
public:
explicit TriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& graph_name,
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: GroupUiBase(rpc_value, base, graph_queue, character_queue)
{
graph_name_ = graph_name;
};
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
void updateForQueue() override;
void updateForQueue(bool check_repeat);
void updateTwiceForQueue(bool check_repeat = true);

protected:
std::string graph_name_;
};

class ChassisTriggerChangeUi : public TriggerChangeUi
{
public:
explicit ChassisTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "chassis", graph_queue)
explicit ChassisTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "chassis", graph_queue, character_queue)
{
if (base.robot_id_ == rm_referee::RobotId::RED_ENGINEER || base.robot_id_ == rm_referee::RobotId::BLUE_ENGINEER)
graph_->setContent("raw");
Expand All @@ -40,9 +62,9 @@ class ChassisTriggerChangeUi : public TriggerChangeUi
else
mode_change_threshold_ = 0.7;
}
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr data);
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr& data);
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;
void updateDbusData(const rm_msgs::DbusData::ConstPtr data);
void updateDbusData(const rm_msgs::DbusData::ConstPtr& data);
void updateCapacityResetStatus();
void checkModeChange();

Expand All @@ -58,8 +80,9 @@ class ChassisTriggerChangeUi : public TriggerChangeUi
class ShooterTriggerChangeUi : public TriggerChangeUi
{
public:
explicit ShooterTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "shooter", graph_queue)
explicit ShooterTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "shooter", graph_queue, character_queue)
{
graph_->setContent("0");
}
Expand All @@ -76,12 +99,13 @@ class ShooterTriggerChangeUi : public TriggerChangeUi
class GimbalTriggerChangeUi : public TriggerChangeUi
{
public:
explicit GimbalTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "gimbal", graph_queue)
explicit GimbalTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "gimbal", graph_queue, character_queue)
{
graph_->setContent("0");
}
void updateGimbalCmdData(const rm_msgs::GimbalCmd ::ConstPtr data);
void updateGimbalCmdData(const rm_msgs::GimbalCmd ::ConstPtr& data);
void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data) override;

private:
Expand All @@ -94,8 +118,9 @@ class GimbalTriggerChangeUi : public TriggerChangeUi
class TargetTriggerChangeUi : public TriggerChangeUi
{
public:
explicit TargetTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "target", graph_queue)
explicit TargetTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "target", graph_queue, character_queue)
{
graph_->setContent("armor");
if (base_.robot_color_ == "red")
Expand All @@ -116,8 +141,9 @@ class TargetTriggerChangeUi : public TriggerChangeUi
class TargetViewAngleTriggerChangeUi : public TriggerChangeUi
{
public:
explicit TargetViewAngleTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "target_scale", graph_queue)
explicit TargetViewAngleTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "target_scale", graph_queue, character_queue)
{
}
void updateTrackID(int id);
Expand All @@ -128,10 +154,12 @@ class TargetViewAngleTriggerChangeUi : public TriggerChangeUi
int track_id_;
};

class PolygonTriggerChangeGroupUi : public GroupUiBase
class PolygonTriggerChangeGroupUi : public TriggerChangeGroupUi
{
public:
explicit PolygonTriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base) : GroupUiBase(rpc_value, base)
explicit PolygonTriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeGroupUi(rpc_value, base, "Polygon", graph_queue, character_queue)
{
ROS_ASSERT(rpc_value.hasMember("points"));
XmlRpc::XmlRpcValue config;
Expand Down Expand Up @@ -171,14 +199,14 @@ class PolygonTriggerChangeGroupUi : public GroupUiBase
}
}
void update() override;
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
};

class CameraTriggerChangeUi : public TriggerChangeUi
{
public:
explicit CameraTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::vector<Graph>* graph_queue)
: TriggerChangeUi(rpc_value, base, "camera", graph_queue)
explicit CameraTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, "camera", graph_queue, character_queue)
{
if (rpc_value.hasMember("camera_name"))
{
Expand Down
Loading

0 comments on commit 892455f

Please sign in to comment.