Skip to content

Commit

Permalink
Merge pull request #113 from chenhuiYu00/dev/polygon_ui
Browse files Browse the repository at this point in the history
Add polygon UI.
  • Loading branch information
ye-luo-xi-tui authored Mar 24, 2023
2 parents 16532de + 4ee48dd commit 25bfb90
Show file tree
Hide file tree
Showing 4 changed files with 88 additions and 12 deletions.
47 changes: 47 additions & 0 deletions rm_referee/include/rm_referee/ui/trigger_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,4 +103,51 @@ class TargetTriggerChangeUi : public TriggerChangeUi
std::string getTargetState(uint8_t target, uint8_t armor_target);
uint8_t det_target_, shoot_frequency_, det_armor_target_, det_color_, gimbal_eject_;
};

class PolygonTriggerChangeGroupUi : public GroupUiBase
{
public:
explicit PolygonTriggerChangeGroupUi(XmlRpc::XmlRpcValue& rpc_value, Base& base) : GroupUiBase(base)
{
ROS_ASSERT(rpc_value.hasMember("points"));
XmlRpc::XmlRpcValue config;

config["type"] = "line";

if (rpc_value["graph_config"].hasMember("color"))
config["color"] = rpc_value["graph_config"]["color"];
else
config["color"] = "cyan";
if (rpc_value["graph_config"].hasMember("width"))
config["width"] = rpc_value["graph_config"]["width"];
else
config["width"] = 2;
XmlRpc::XmlRpcValue points = rpc_value["points"];
config["start_position"].setSize(2);
config["end_position"].setSize(2);
for (int i = 1; i <= points.size(); i++)
{
if (i != points.size())
{
config["start_position"][0] = points[i - 1][0];
config["start_position"][1] = points[i - 1][1];
config["end_position"][0] = points[i][0];
config["end_position"][1] = points[i][1];
}
else
{
// Connect first and last point
config["start_position"][0] = points[i - 1][0];
config["start_position"][1] = points[i - 1][1];
config["end_position"][0] = points[0][0];
config["end_position"][1] = points[0][1];
}
graph_vector_.insert(
std::make_pair<std::string, Graph*>("graph_" + std::to_string(i), new Graph(config, base_, id_++)));
}
}
virtual void display();
virtual void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false){};
};

} // namespace rm_referee
23 changes: 17 additions & 6 deletions rm_referee/include/rm_referee/ui/ui_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ class UiBase
explicit UiBase(Base& base) : base_(base), tf_listener_(tf_buffer_){};
~UiBase() = default;
virtual void add();
virtual void erasure();
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data){};
virtual void updateManualCmdData(const rm_msgs::ManualToReferee::ConstPtr data, const ros::Time& last_get_data_time){};

Expand All @@ -30,18 +31,28 @@ class UiBase
tf2_ros::TransformListener tf_listener_;
};

class FixedUi : public UiBase
class GroupUiBase : public UiBase
{
public:
explicit FixedUi(XmlRpc::XmlRpcValue& rpc_value, Base& base) : UiBase(base)
explicit GroupUiBase(Base& base) : UiBase(base){};
~GroupUiBase() = default;
virtual void add() override;
virtual void erasure() override;
virtual void display(){};

protected:
std::map<std::string, Graph*> graph_vector_;
};

class FixedUi : public GroupUiBase
{
public:
explicit FixedUi(XmlRpc::XmlRpcValue& rpc_value, Base& base) : GroupUiBase(base)
{
for (int i = 0; i < static_cast<int>(rpc_value.size()); i++)
graph_vector_.insert(
std::pair<std::string, Graph*>(rpc_value[i]["name"], new Graph(rpc_value[i]["config"], base_, id_++)));
};
void add() override;
void display();

std::map<std::string, Graph*> graph_vector_;
};

} // namespace rm_referee
11 changes: 11 additions & 0 deletions rm_referee/src/ui/trigger_change_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,4 +240,15 @@ void TargetTriggerChangeUi::updateShootStateData(const rm_msgs::ShootState::Cons
{
display();
}

void PolygonTriggerChangeGroupUi::display()
{
for (auto graph : graph_vector_)
{
graph.second->setOperation(rm_referee::GraphOperation::UPDATE);
graph.second->display();
graph.second->sendUi(ros::Time::now());
}
}

} // namespace rm_referee
19 changes: 13 additions & 6 deletions rm_referee/src/ui/ui_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,23 +14,30 @@ void UiBase::add()
graph_->sendUi(ros::Time::now());
}

void FixedUi ::add()
void UiBase::erasure()
{
graph_->setOperation(rm_referee::GraphOperation::DELETE);
graph_->display(true);
graph_->sendUi(ros::Time::now());
}

void GroupUiBase::add()
{
for (auto graph : graph_vector_)
{
graph.second->setOperation(rm_referee::GraphOperation::ADD);
graph.second->display();
graph.second->sendUi(ros::Time::now());
}
};
}

void FixedUi::display()
void GroupUiBase::erasure()
{
for (auto graph : graph_vector_)
{
graph.second->setOperation(rm_referee::GraphOperation::UPDATE);
graph.second->display();
graph.second->sendUi(ros::Time::now());
graph_->setOperation(rm_referee::GraphOperation::DELETE);
graph_->display(true);
graph_->sendUi(ros::Time::now());
}
}

Expand Down

0 comments on commit 25bfb90

Please sign in to comment.