rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
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 <std_msgs/Float64.h>
47
48namespace rm_common
49{
51{
52public:
53 HeatLimit(ros::NodeHandle& nh)
54
55 {
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")
74 bullet_heat_ = 100.;
75 else
76 bullet_heat_ = 10.;
77 local_heat_pub_ = nh.advertise<std_msgs::Float64>("/local_heat_state/local_cooling_heat", 10);
78 shoot_state_sub_ =
79 nh.subscribe<rm_msgs::LocalHeatState>("/local_heat_state/shooter_state", 50, &HeatLimit::heatCB, this);
80 timer_ = nh.createTimer(ros::Duration(0.1), std::bind(&HeatLimit::timerCB, this));
81 }
82
83 typedef enum
84 {
85 LOW = 0,
86 HIGH = 1,
87 BURST = 2,
88 MINIMAL = 3
90
91 void heatCB(const rm_msgs::LocalHeatStateConstPtr& msg)
92 {
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;
97 }
98
99 void timerCB()
100 {
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);
109 }
110
111 void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
112 {
113 shooter_cooling_limit_ = data.shooter_cooling_limit - heat_protect_threshold_;
114 shooter_cooling_rate_ = data.shooter_cooling_rate;
115 }
116
117 void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
118 {
119 if (type_ == "ID1_17MM")
120 {
121 shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
122 }
123 else if (type_ == "ID2_17MM")
124 {
125 shooter_cooling_heat_ = data.shooter_id_2_17_mm_cooling_heat;
126 }
127 else if (type_ == "ID1_42MM")
128 {
129 shooter_cooling_heat_ = data.shooter_id_1_42_mm_cooling_heat;
130 }
131 }
132
133 void setRefereeStatus(bool status)
134 {
135 referee_is_online_ = status;
136 }
137
138 double getShootFrequency() const
139 {
140 std::lock_guard<std::mutex> lock(heat_mutex_);
141 if (state_ == BURST)
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_)
146 return 0.0;
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_;
153 else
154 return shoot_frequency_;
155 }
156
158 {
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;
166 return -1; // TODO unsafe!
167 }
168
170 {
171 return shooter_cooling_limit_;
172 }
173
175 {
176 return shooter_cooling_heat_;
177 }
178
179 void setShootFrequency(uint8_t mode)
180 {
181 state_ = mode;
182 }
183
185 {
186 return state_;
187 }
188
189private:
190 void updateExpectShootFrequency()
191 {
192 if (state_ == HeatLimit::BURST)
193 {
194 shoot_frequency_ = burst_shoot_frequency_;
195 burst_flag_ = true;
196 }
197 else if (state_ == HeatLimit::LOW)
198 {
199 shoot_frequency_ = low_shoot_frequency_;
200 burst_flag_ = false;
201 }
202 else if (state_ == HeatLimit::HIGH)
203 {
204 shoot_frequency_ = high_shoot_frequency_;
205 burst_flag_ = false;
206 }
207 else if (state_ == HeatLimit::MINIMAL)
208 {
209 shoot_frequency_ = minimal_shoot_frequency_;
210 burst_flag_ = false;
211 }
212 else
213 {
214 shoot_frequency_ = safe_shoot_frequency_;
215 burst_flag_ = false;
216 }
217 }
218
219 uint8_t state_{};
220 std::string type_{};
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_{};
224
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_{};
228
229 ros::Publisher local_heat_pub_;
230 ros::Subscriber shoot_state_sub_;
231 ros::Timer timer_;
232
233 mutable std::mutex heat_mutex_;
234};
235
236} // namespace rm_common
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