Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class RefereeBase
virtual void interactiveDataCallBack(const rm_referee::InteractiveData& interactive_data,
const ros::Time& last_get_data_time);
virtual void eventDataCallBack(const rm_msgs::EventData& event_data, const ros::Time& last_get_data_time);
virtual void updateHeroHitDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data);
virtual void updateGameRobotHpDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data);
virtual void supplyBulletDataCallBack(const rm_msgs::SupplyProjectileAction& data);
virtual void updateShootDataDataCallBack(const rm_msgs::ShootData& msg);
virtual void updateBulletRemainData(const rm_referee::BulletNumData& data);
Expand Down Expand Up @@ -124,6 +124,7 @@ class RefereeBase
*engineer_joint3_time_change_ui{};
TargetDistanceTimeChangeUi* target_distance_time_change_ui_{};
FriendBulletsTimeChangeGroupUi* friend_bullets_time_change_group_ui_{};
TargetHpTimeChangeUi* target_hp_time_change_ui_{};

DroneTowardsTimeChangeGroupUi* drone_towards_time_change_group_ui_{};
StringTriggerChangeUi *servo_mode_trigger_change_ui_{}, *stone_num_trigger_change_ui_{},
Expand Down
27 changes: 27 additions & 0 deletions rm_referee/include/rm_referee/ui/time_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -394,4 +394,31 @@ class FriendBulletsTimeChangeGroupUi : public TimeChangeGroupUi
int hero_bullets_{ 1 }, standard3_bullets_{ 3 }, standard4_bullets_{ 4 }, standard5_bullets_{ 5 };
};

class TargetHpTimeChangeUi : public TimeChangeUi
{
public:
explicit TargetHpTimeChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: TimeChangeUi(rpc_value, base, "target_hp", graph_queue, character_queue)
{
if (rpc_value.hasMember("enemy_id"))
{
XmlRpc::XmlRpcValue& enemy_id = rpc_value["enemy_id"];
for (int i = 0; i < enemy_id.size(); i++)
{
int id = static_cast<int>(enemy_id[i]);
enemy_robot_hp_[id] = 0;
}
}
}
void setEnemyHp(const rm_msgs::GameRobotHp& data);
void updateTrackID(int id);
void updateTargeHptData();

private:
void updateConfig() override;
std::map<int, int> enemy_robot_hp_;
int target_hp_{}, target_id_{};
};

} // namespace rm_referee
2 changes: 1 addition & 1 deletion rm_referee/src/referee.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ int Referee::unpack(uint8_t* rx_data)
game_robot_hp_data.red_base_hp = game_robot_hp_ref.red_base_hp;
game_robot_hp_data.stamp = last_get_data_time_;

referee_ui_.updateHeroHitDataCallBack(game_robot_hp_data);
referee_ui_.updateGameRobotHpDataCallBack(game_robot_hp_data);
game_robot_hp_pub_.publish(game_robot_hp_data);
break;
}
Expand Down
10 changes: 9 additions & 1 deletion rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,8 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
if (rpc_value[i]["name"] == "friend_bullets")
friend_bullets_time_change_group_ui_ =
new FriendBulletsTimeChangeGroupUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "target_hp")
target_hp_time_change_ui_ = new TargetHpTimeChangeUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
}

ui_nh.getParam("fixed", rpc_value);
Expand Down Expand Up @@ -268,6 +270,8 @@ void RefereeBase::addUi()
target_distance_time_change_ui_->addForQueue();
if (friend_bullets_time_change_group_ui_)
friend_bullets_time_change_group_ui_->addForQueue();
if (target_hp_time_change_ui_)
target_hp_time_change_ui_->addForQueue();
if (visualize_state_trigger_change_ui_)
visualize_state_trigger_change_ui_->addForQueue();
add_ui_times_++;
Expand Down Expand Up @@ -365,10 +369,12 @@ void RefereeBase::robotStatusDataCallBack(const rm_msgs::GameRobotStatus& data,
fixed_ui_->updateForQueue();
}

void RefereeBase::updateHeroHitDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data)
void RefereeBase::updateGameRobotHpDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data)
{
if (hero_hit_flash_ui_)
hero_hit_flash_ui_->updateHittingConfig(game_robot_hp_data);
if (target_hp_time_change_ui_)
target_hp_time_change_ui_->setEnemyHp(game_robot_hp_data);
}
void RefereeBase::gameStatusDataCallBack(const rm_msgs::GameStatus& data, const ros::Time& last_get_data_time)
{
Expand Down Expand Up @@ -514,6 +520,8 @@ void RefereeBase::trackCallBack(const rm_msgs::TrackDataConstPtr& data)
target_view_angle_trigger_change_ui_->updateTrackID(data->id);
if (target_distance_time_change_ui_ && !is_adding_)
target_distance_time_change_ui_->updateTargetDistanceData(data);
if (target_hp_time_change_ui_ && !is_adding_)
target_hp_time_change_ui_->updateTrackID(data->id);
}
void RefereeBase::balanceStateCallback(const rm_msgs::BalanceStateConstPtr& data)
{
Expand Down
43 changes: 43 additions & 0 deletions rm_referee/src/ui/time_change_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -514,4 +514,47 @@ void FriendBulletsTimeChangeGroupUi::updateConfig()
}
}

void TargetHpTimeChangeUi::setEnemyHp(const rm_msgs::GameRobotHp& data)
{
bool is_enemy_red = base_.robot_id_ > 100;
if (is_enemy_red)
{
enemy_robot_hp_[1] = data.red_1_robot_hp;
enemy_robot_hp_[2] = data.red_2_robot_hp;
enemy_robot_hp_[3] = data.red_3_robot_hp;
enemy_robot_hp_[4] = data.red_4_robot_hp;
enemy_robot_hp_[7] = data.red_7_robot_hp;
}
else
{
enemy_robot_hp_[1] = data.blue_1_robot_hp;
enemy_robot_hp_[2] = data.blue_2_robot_hp;
enemy_robot_hp_[3] = data.blue_3_robot_hp;
enemy_robot_hp_[4] = data.blue_4_robot_hp;
enemy_robot_hp_[7] = data.blue_7_robot_hp;
}
}

void TargetHpTimeChangeUi::updateTrackID(int id)
{
target_id_ = id;
updateTargeHptData();
}

void TargetHpTimeChangeUi::updateTargeHptData()
{
auto it = enemy_robot_hp_.find(target_id_);
target_hp_ = it == enemy_robot_hp_.end() ? 0 : it->second;
updateForQueue();
}

void TargetHpTimeChangeUi::updateConfig()
{
graph_->setIntNum(target_hp_);
if (target_hp_ > 50)
graph_->setColor(rm_referee::GraphColor::GREEN);
else
graph_->setColor(rm_referee::GraphColor::ORANGE);
}

} // namespace rm_referee
Loading