42#include <rm_msgs/GameRobotStatus.h>
43#include <rm_msgs/PowerHeatData.h>
44#include <rm_msgs/ShootCmd.h>
45#include <rm_msgs/LocalHeatState.h>
46#include <rm_msgs/LocalHeatData.h>
47#include <std_msgs/Float64.h>
57 if (!nh.getParam(
"low_shoot_frequency", low_shoot_frequency_))
58 ROS_ERROR(
"Low shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
59 if (!nh.getParam(
"high_shoot_frequency", high_shoot_frequency_))
60 ROS_ERROR(
"High shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
61 if (!nh.getParam(
"burst_shoot_frequency", burst_shoot_frequency_))
62 ROS_ERROR(
"Burst shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
63 if (!nh.getParam(
"minimal_shoot_frequency", minimal_shoot_frequency_))
64 ROS_ERROR(
"Minimal shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
65 if (!nh.getParam(
"safe_shoot_frequency", safe_shoot_frequency_))
66 ROS_ERROR(
"Safe shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
67 if (!nh.getParam(
"heat_coeff", heat_coeff_))
68 ROS_ERROR(
"Heat coeff no defined (namespace: %s)", nh.getNamespace().c_str());
69 if (!nh.getParam(
"type", type_))
70 ROS_ERROR(
"Shooter type no defined (namespace: %s)", nh.getNamespace().c_str());
71 if (!nh.getParam(
"local_heat_protect_threshold", heat_protect_threshold_))
72 ROS_ERROR(
"Local heat protect threshold no defined (namespace: %s)", nh.getNamespace().c_str());
73 nh.param(
"use_local_heat", use_local_heat_,
true);
74 if (type_ ==
"ID1_42MM")
78 local_heat_pub_ = nh.advertise<rm_msgs::LocalHeatData>(
"/local_heat_state/local_cooling_heat", 10);
80 nh.subscribe<rm_msgs::LocalHeatState>(
"/local_heat_state/shooter_state", 50, &
HeatLimit::heatCB,
this);
92 void heatCB(
const rm_msgs::LocalHeatStateConstPtr& msg)
94 std::lock_guard<std::mutex> lock(heat_mutex_);
95 if (msg->has_shoot && last_shoot_state_ != msg->has_shoot)
97 local_shooter_cooling_heat_ += bullet_heat_;
98 if (local_shooter_cooling_heat_ > 0)
101 last_shoot_state_ = msg->has_shoot;
106 std::lock_guard<std::mutex> lock(heat_mutex_);
107 if (local_shooter_cooling_heat_ > 0.0)
108 local_shooter_cooling_heat_ -= shooter_cooling_rate_ * 0.1;
109 if (local_shooter_cooling_heat_ < 0.0)
111 local_shooter_cooling_heat_ = 0.0;
114 local_heat_pub_data_.once_shoot_num = once_shoot_num_;
115 local_heat_pub_data_.local_shooter_cooling_heat = local_shooter_cooling_heat_;
116 local_heat_pub_.publish(local_heat_pub_data_);
121 shooter_cooling_limit_ = data.shooter_cooling_limit - heat_protect_threshold_;
122 shooter_cooling_rate_ = data.shooter_cooling_rate;
127 if (type_ ==
"ID1_17MM")
129 shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
131 else if (type_ ==
"ID2_17MM")
133 shooter_cooling_heat_ = data.shooter_id_2_17_mm_cooling_heat;
135 else if (type_ ==
"ID1_42MM")
137 shooter_cooling_heat_ = data.shooter_id_1_42_mm_cooling_heat;
143 referee_is_online_ = status;
148 std::lock_guard<std::mutex> lock(heat_mutex_);
150 return shoot_frequency_;
151 double shooter_cooling_heat =
152 (use_local_heat_ || !referee_is_online_) ? local_shooter_cooling_heat_ : shooter_cooling_heat_;
153 if (shooter_cooling_limit_ - shooter_cooling_heat < bullet_heat_)
155 else if (shooter_cooling_limit_ - shooter_cooling_heat == bullet_heat_)
156 return shooter_cooling_rate_ / bullet_heat_;
157 else if (shooter_cooling_limit_ - shooter_cooling_heat <= bullet_heat_ * heat_coeff_)
158 return (shooter_cooling_limit_ - shooter_cooling_heat) / (bullet_heat_ * heat_coeff_) *
159 (shoot_frequency_ - shooter_cooling_rate_ / bullet_heat_) +
160 shooter_cooling_rate_ / bullet_heat_;
162 return shoot_frequency_;
167 updateExpectShootFrequency();
168 if (type_ ==
"ID1_17MM")
169 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
170 else if (type_ ==
"ID2_17MM")
171 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
172 else if (type_ ==
"ID1_42MM")
173 return rm_msgs::ShootCmd::SPEED_16M_PER_SECOND;
179 return shooter_cooling_limit_;
184 return shooter_cooling_heat_;
198 void updateExpectShootFrequency()
202 shoot_frequency_ = burst_shoot_frequency_;
207 shoot_frequency_ = low_shoot_frequency_;
212 shoot_frequency_ = high_shoot_frequency_;
217 shoot_frequency_ = minimal_shoot_frequency_;
222 shoot_frequency_ = safe_shoot_frequency_;
229 bool burst_flag_ =
false;
230 double bullet_heat_, safe_shoot_frequency_{}, heat_coeff_{}, shoot_frequency_{}, low_shoot_frequency_{},
231 high_shoot_frequency_{}, burst_shoot_frequency_{}, minimal_shoot_frequency_{};
233 bool referee_is_online_, use_local_heat_, last_shoot_state_{};
234 int shooter_cooling_limit_, shooter_cooling_rate_, shooter_cooling_heat_;
235 double local_shooter_cooling_heat_{}, heat_protect_threshold_{};
236 int once_shoot_num_{};
238 ros::Publisher local_heat_pub_;
239 ros::Subscriber shoot_state_sub_;
242 rm_msgs::LocalHeatData local_heat_pub_data_;
244 mutable std::mutex heat_mutex_;
Definition heat_limit.h:52
int getCoolingLimit()
Definition heat_limit.h:177
double getShootFrequency() const
Definition heat_limit.h:146
void heatCB(const rm_msgs::LocalHeatStateConstPtr &msg)
Definition heat_limit.h:92
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:119
ShootHz
Definition heat_limit.h:85
@ LOW
Definition heat_limit.h:86
@ HIGH
Definition heat_limit.h:87
@ BURST
Definition heat_limit.h:88
@ MINIMAL
Definition heat_limit.h:89
HeatLimit(ros::NodeHandle &nh)
Definition heat_limit.h:54
void setRefereeStatus(bool status)
Definition heat_limit.h:141
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:187
int getCoolingHeat()
Definition heat_limit.h:182
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:165
bool getShootFrequencyMode() const
Definition heat_limit.h:192
void timerCB()
Definition heat_limit.h:104
Definition calibration_queue.h:44