Skip to content

Commit

Permalink
Merge pull request #212 from GuraMumei/add_battlefield_info_sender
Browse files Browse the repository at this point in the history
Modify ui
  • Loading branch information
d0h0s authored Apr 2, 2024
2 parents 855ed0f + 46f9ba0 commit 4860ed7
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 9 deletions.
2 changes: 1 addition & 1 deletion rm_referee/src/referee.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,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_.updateEnemyHeroState(game_robot_hp_data, last_get_data_time_);
// referee_ui_.updateEnemyHeroState(game_robot_hp_data, last_get_data_time_);
referee_ui_.updateHeroStateDataCallBack(game_robot_hp_data, last_get_data_time_);
game_robot_hp_pub_.publish(game_robot_hp_data);
break;
Expand Down
22 changes: 14 additions & 8 deletions rm_referee/src/ui/time_change_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,12 +214,12 @@ void LaneLineTimeChangeGroupUi::updateConfig()

void LaneLineTimeChangeGroupUi::updateJointStateData(const sensor_msgs::JointState::ConstPtr data, const ros::Time& time)
{
if (!tf_buffer_.canTransform(reference_frame_, "yaw", ros::Time(0)))
if (!tf_buffer_.canTransform("yaw", reference_frame_, ros::Time(0)))
return;
try
{
double roll, pitch, yaw;
quatToRPY(tf_buffer_.lookupTransform(reference_frame_, "yaw", ros::Time(0)).transform.rotation, roll, pitch, yaw);
quatToRPY(tf_buffer_.lookupTransform("yaw", reference_frame_, ros::Time(0)).transform.rotation, roll, pitch, yaw);
pitch_angle_ = pitch;
}
catch (tf2::TransformException& ex)
Expand Down Expand Up @@ -324,12 +324,18 @@ void JointPositionTimeChangeUi::updateJointStateData(const sensor_msgs::JointSta

void BulletTimeChangeUi::updateBulletData(const rm_msgs::BulletAllowance& data, const ros::Time& time)
{
if (bullet_allowance_num_17_mm_ > data.bullet_allowance_num_17_mm && data.bullet_allowance_num_17_mm >= 0)
bullet_num_17_mm_ += (bullet_allowance_num_17_mm_ - data.bullet_allowance_num_17_mm);
if (bullet_allowance_num_42_mm_ > data.bullet_allowance_num_42_mm && data.bullet_allowance_num_42_mm >= 0)
bullet_num_42_mm_ += (bullet_allowance_num_42_mm_ - data.bullet_allowance_num_42_mm);
bullet_allowance_num_17_mm_ = data.bullet_allowance_num_17_mm;
bullet_allowance_num_42_mm_ = data.bullet_allowance_num_42_mm;
if (data.bullet_allowance_num_17_mm >= 0 && data.bullet_allowance_num_17_mm < 1000)
{
if (bullet_allowance_num_17_mm_ > data.bullet_allowance_num_17_mm)
bullet_num_17_mm_ += (bullet_allowance_num_17_mm_ - data.bullet_allowance_num_17_mm);
bullet_allowance_num_17_mm_ = data.bullet_allowance_num_17_mm;
}
if (data.bullet_allowance_num_42_mm >= 0 && data.bullet_allowance_num_42_mm < 1000)
{
if (bullet_allowance_num_42_mm_ > data.bullet_allowance_num_42_mm)
bullet_num_42_mm_ += (bullet_allowance_num_42_mm_ - data.bullet_allowance_num_42_mm);
bullet_allowance_num_42_mm_ = data.bullet_allowance_num_42_mm;
}
updateForQueue();
}

Expand Down

0 comments on commit 4860ed7

Please sign in to comment.