rm_control
Loading...
Searching...
No Matches
heat_limit.h
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2021, Qiayuan Liao
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * * Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * * Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24 * ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33
34//
35// Created by qiayuan on 5/19/21.
36//
37
38#pragma once
39
40#include <ros/ros.h>
41#include <mutex>
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>
48
49namespace rm_common
50{
52{
53public:
54 HeatLimit(ros::NodeHandle& nh)
55
56 {
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")
75 bullet_heat_ = 100.;
76 else
77 bullet_heat_ = 10.;
78 local_heat_pub_ = nh.advertise<rm_msgs::LocalHeatData>("/local_heat_state/local_cooling_heat", 10);
79 shoot_state_sub_ =
80 nh.subscribe<rm_msgs::LocalHeatState>("/local_heat_state/shooter_state", 50, &HeatLimit::heatCB, this);
81 timer_ = nh.createTimer(ros::Duration(0.1), std::bind(&HeatLimit::timerCB, this));
82 }
83
84 typedef enum
85 {
86 LOW = 0,
87 HIGH = 1,
88 BURST = 2,
89 MINIMAL = 3
91
92 void heatCB(const rm_msgs::LocalHeatStateConstPtr& msg)
93 {
94 std::lock_guard<std::mutex> lock(heat_mutex_);
95 if (msg->has_shoot && last_shoot_state_ != msg->has_shoot)
96 {
97 local_shooter_cooling_heat_ += bullet_heat_;
98 if (local_shooter_cooling_heat_ > 0)
99 once_shoot_num_++;
100 }
101 last_shoot_state_ = msg->has_shoot;
102 }
103
104 void timerCB()
105 {
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)
110 {
111 local_shooter_cooling_heat_ = 0.0;
112 once_shoot_num_ = 0;
113 }
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_);
117 }
118
119 void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
120 {
121 shooter_cooling_limit_ = data.shooter_cooling_limit - heat_protect_threshold_;
122 shooter_cooling_rate_ = data.shooter_cooling_rate;
123 }
124
125 void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
126 {
127 if (type_ == "ID1_17MM")
128 {
129 shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
130 }
131 else if (type_ == "ID2_17MM")
132 {
133 // RoboMaster 2026 protocol only reports one 17mm barrel heat field.
134 shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
135 }
136 else if (type_ == "ID1_42MM")
137 {
138 shooter_cooling_heat_ = data.shooter_id_1_42_mm_cooling_heat;
139 }
140 }
141
142 void setRefereeStatus(bool status)
143 {
144 referee_is_online_ = status;
145 }
146
147 double getShootFrequency() const
148 {
149 std::lock_guard<std::mutex> lock(heat_mutex_);
150 if (state_ == BURST)
151 return shoot_frequency_;
152 double shooter_cooling_heat =
153 (use_local_heat_ || !referee_is_online_) ? local_shooter_cooling_heat_ : shooter_cooling_heat_;
154 if (shooter_cooling_limit_ - shooter_cooling_heat < bullet_heat_)
155 return 0.0;
156 else if (shooter_cooling_limit_ - shooter_cooling_heat == bullet_heat_)
157 return shooter_cooling_rate_ / bullet_heat_;
158 else if (shooter_cooling_limit_ - shooter_cooling_heat <= bullet_heat_ * heat_coeff_)
159 return (shooter_cooling_limit_ - shooter_cooling_heat) / (bullet_heat_ * heat_coeff_) *
160 (shoot_frequency_ - shooter_cooling_rate_ / bullet_heat_) +
161 shooter_cooling_rate_ / bullet_heat_;
162 else
163 return shoot_frequency_;
164 }
165
167 {
168 updateExpectShootFrequency();
169 if (type_ == "ID1_17MM")
170 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
171 else if (type_ == "ID2_17MM")
172 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
173 else if (type_ == "ID1_42MM")
174 return rm_msgs::ShootCmd::SPEED_16M_PER_SECOND;
175 return -1; // TODO unsafe!
176 }
177
179 {
180 return shooter_cooling_limit_;
181 }
182
184 {
185 return shooter_cooling_heat_;
186 }
187
188 void setShootFrequency(uint8_t mode)
189 {
190 state_ = mode;
191 }
192
194 {
195 return state_;
196 }
197
198private:
199 void updateExpectShootFrequency()
200 {
201 if (state_ == HeatLimit::BURST)
202 {
203 shoot_frequency_ = burst_shoot_frequency_;
204 burst_flag_ = true;
205 }
206 else if (state_ == HeatLimit::LOW)
207 {
208 shoot_frequency_ = low_shoot_frequency_;
209 burst_flag_ = false;
210 }
211 else if (state_ == HeatLimit::HIGH)
212 {
213 shoot_frequency_ = high_shoot_frequency_;
214 burst_flag_ = false;
215 }
216 else if (state_ == HeatLimit::MINIMAL)
217 {
218 shoot_frequency_ = minimal_shoot_frequency_;
219 burst_flag_ = false;
220 }
221 else
222 {
223 shoot_frequency_ = safe_shoot_frequency_;
224 burst_flag_ = false;
225 }
226 }
227
228 uint8_t state_{};
229 std::string type_{};
230 bool burst_flag_ = false;
231 double bullet_heat_, safe_shoot_frequency_{}, heat_coeff_{}, shoot_frequency_{}, low_shoot_frequency_{},
232 high_shoot_frequency_{}, burst_shoot_frequency_{}, minimal_shoot_frequency_{};
233
234 bool referee_is_online_, use_local_heat_, last_shoot_state_{};
235 int shooter_cooling_limit_, shooter_cooling_rate_, shooter_cooling_heat_;
236 double local_shooter_cooling_heat_{}, heat_protect_threshold_{};
237 int once_shoot_num_{};
238
239 ros::Publisher local_heat_pub_;
240 ros::Subscriber shoot_state_sub_;
241 ros::Timer timer_;
242
243 rm_msgs::LocalHeatData local_heat_pub_data_;
244
245 mutable std::mutex heat_mutex_;
246};
247
248} // namespace rm_common
Definition heat_limit.h:52
int getCoolingLimit()
Definition heat_limit.h:178
double getShootFrequency() const
Definition heat_limit.h:147
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:142
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:188
int getCoolingHeat()
Definition heat_limit.h:183
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:166
bool getShootFrequencyMode() const
Definition heat_limit.h:193
void timerCB()
Definition heat_limit.h:104
Definition calibration_queue.h:44