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 <std_msgs/Float64.h>
56 if (!nh.getParam(
"low_shoot_frequency", low_shoot_frequency_))
57 ROS_ERROR(
"Low shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
58 if (!nh.getParam(
"high_shoot_frequency", high_shoot_frequency_))
59 ROS_ERROR(
"High shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
60 if (!nh.getParam(
"burst_shoot_frequency", burst_shoot_frequency_))
61 ROS_ERROR(
"Burst shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
62 if (!nh.getParam(
"minimal_shoot_frequency", minimal_shoot_frequency_))
63 ROS_ERROR(
"Minimal shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
64 if (!nh.getParam(
"safe_shoot_frequency", safe_shoot_frequency_))
65 ROS_ERROR(
"Safe shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
66 if (!nh.getParam(
"heat_coeff", heat_coeff_))
67 ROS_ERROR(
"Heat coeff no defined (namespace: %s)", nh.getNamespace().c_str());
68 if (!nh.getParam(
"type", type_))
69 ROS_ERROR(
"Shooter type no defined (namespace: %s)", nh.getNamespace().c_str());
70 if (!nh.getParam(
"local_heat_protect_threshold", heat_protect_threshold_))
71 ROS_ERROR(
"Local heat protect threshold no defined (namespace: %s)", nh.getNamespace().c_str());
72 nh.param(
"use_local_heat", use_local_heat_,
true);
73 if (type_ ==
"ID1_42MM")
77 local_heat_pub_ = nh.advertise<std_msgs::Float64>(
"/local_heat_state/local_cooling_heat", 10);
79 nh.subscribe<rm_msgs::LocalHeatState>(
"/local_heat_state/shooter_state", 50, &
HeatLimit::heatCB,
this);
91 void heatCB(
const rm_msgs::LocalHeatStateConstPtr& msg)
93 std::lock_guard<std::mutex> lock(heat_mutex_);
94 if (msg->has_shoot && last_shoot_state_ != msg->has_shoot)
95 local_shooter_cooling_heat_ += bullet_heat_;
96 last_shoot_state_ = msg->has_shoot;
91 void heatCB(
const rm_msgs::LocalHeatStateConstPtr& msg) {
…}
101 std::lock_guard<std::mutex> lock(heat_mutex_);
102 if (local_shooter_cooling_heat_ > 0.0)
103 local_shooter_cooling_heat_ -= shooter_cooling_rate_ * 0.1;
104 if (local_shooter_cooling_heat_ < 0.0)
105 local_shooter_cooling_heat_ = 0.0;
106 std_msgs::Float64 msg;
107 msg.data = local_shooter_cooling_heat_;
108 local_heat_pub_.publish(msg);
113 shooter_cooling_limit_ = data.shooter_cooling_limit - heat_protect_threshold_;
114 shooter_cooling_rate_ = data.shooter_cooling_rate;
119 if (type_ ==
"ID1_17MM")
121 shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
123 else if (type_ ==
"ID2_17MM")
125 shooter_cooling_heat_ = data.shooter_id_2_17_mm_cooling_heat;
127 else if (type_ ==
"ID1_42MM")
129 shooter_cooling_heat_ = data.shooter_id_1_42_mm_cooling_heat;
135 referee_is_online_ = status;
140 std::lock_guard<std::mutex> lock(heat_mutex_);
142 return shoot_frequency_;
143 double shooter_cooling_heat =
144 (use_local_heat_ || !referee_is_online_) ? local_shooter_cooling_heat_ : shooter_cooling_heat_;
145 if (shooter_cooling_limit_ - shooter_cooling_heat < bullet_heat_)
147 else if (shooter_cooling_limit_ - shooter_cooling_heat == bullet_heat_)
148 return shooter_cooling_rate_ / bullet_heat_;
149 else if (shooter_cooling_limit_ - shooter_cooling_heat <= bullet_heat_ * heat_coeff_)
150 return (shooter_cooling_limit_ - shooter_cooling_heat) / (bullet_heat_ * heat_coeff_) *
151 (shoot_frequency_ - shooter_cooling_rate_ / bullet_heat_) +
152 shooter_cooling_rate_ / bullet_heat_;
154 return shoot_frequency_;
159 updateExpectShootFrequency();
160 if (type_ ==
"ID1_17MM")
161 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
162 else if (type_ ==
"ID2_17MM")
163 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
164 else if (type_ ==
"ID1_42MM")
165 return rm_msgs::ShootCmd::SPEED_16M_PER_SECOND;
171 return shooter_cooling_limit_;
176 return shooter_cooling_heat_;
190 void updateExpectShootFrequency()
194 shoot_frequency_ = burst_shoot_frequency_;
199 shoot_frequency_ = low_shoot_frequency_;
204 shoot_frequency_ = high_shoot_frequency_;
209 shoot_frequency_ = minimal_shoot_frequency_;
214 shoot_frequency_ = safe_shoot_frequency_;
221 bool burst_flag_ =
false;
222 double bullet_heat_, safe_shoot_frequency_{}, heat_coeff_{}, shoot_frequency_{}, low_shoot_frequency_{},
223 high_shoot_frequency_{}, burst_shoot_frequency_{}, minimal_shoot_frequency_{};
225 bool referee_is_online_, use_local_heat_, last_shoot_state_{};
226 int shooter_cooling_limit_, shooter_cooling_rate_, shooter_cooling_heat_;
227 double local_shooter_cooling_heat_{}, heat_protect_threshold_{};
229 ros::Publisher local_heat_pub_;
230 ros::Subscriber shoot_state_sub_;
233 mutable std::mutex heat_mutex_;
Definition heat_limit.h:51
int getCoolingLimit()
Definition heat_limit.h:169
double getShootFrequency() const
Definition heat_limit.h:138
void heatCB(const rm_msgs::LocalHeatStateConstPtr &msg)
Definition heat_limit.h:91
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:111
ShootHz
Definition heat_limit.h:84
@ LOW
Definition heat_limit.h:85
@ HIGH
Definition heat_limit.h:86
@ BURST
Definition heat_limit.h:87
@ MINIMAL
Definition heat_limit.h:88
HeatLimit(ros::NodeHandle &nh)
Definition heat_limit.h:53
void setRefereeStatus(bool status)
Definition heat_limit.h:133
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:179
int getCoolingHeat()
Definition heat_limit.h:174
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:117
int getSpeedLimit()
Definition heat_limit.h:157
bool getShootFrequencyMode() const
Definition heat_limit.h:184
void timerCB()
Definition heat_limit.h:99
Definition calibration_queue.h:44