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 <rm_msgs/GameRobotStatus.h>
42 #include <rm_msgs/PowerHeatData.h>
43 #include <rm_msgs/ShootCmd.h>
44 #include <rm_msgs/LocalHeatState.h>
45 #include <std_msgs/Float64.h>
46 
47 namespace rm_common
48 {
49 class HeatLimit
50 {
51 public:
53 
54  {
55  if (!nh.getParam("low_shoot_frequency", low_shoot_frequency_))
56  ROS_ERROR("Low shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
57  if (!nh.getParam("high_shoot_frequency", high_shoot_frequency_))
58  ROS_ERROR("High shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
59  if (!nh.getParam("burst_shoot_frequency", burst_shoot_frequency_))
60  ROS_ERROR("Burst shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
61  if (!nh.getParam("minimal_shoot_frequency", minimal_shoot_frequency_))
62  ROS_ERROR("Minimal shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
63  if (!nh.getParam("safe_shoot_frequency", safe_shoot_frequency_))
64  ROS_ERROR("Safe shoot frequency no defined (namespace: %s)", nh.getNamespace().c_str());
65  if (!nh.getParam("heat_coeff", heat_coeff_))
66  ROS_ERROR("Heat coeff no defined (namespace: %s)", nh.getNamespace().c_str());
67  if (!nh.getParam("type", type_))
68  ROS_ERROR("Shooter type no defined (namespace: %s)", nh.getNamespace().c_str());
69  nh.param("use_local_heat", use_local_heat_, true);
70  if (type_ == "ID1_42MM")
71  bullet_heat_ = 100.;
72  else
73  bullet_heat_ = 10.;
74  local_heat_pub_ = nh.advertise<std_msgs::Float64>("/local_heat_state/local_cooling_heat", 10);
76  nh.subscribe<rm_msgs::LocalHeatState>("/local_heat_state/shooter_state", 50, &HeatLimit::heatCB, this);
77  timer_ = nh.createTimer(ros::Duration(0.1), std::bind(&HeatLimit::timerCB, this));
78  }
79 
80  typedef enum
81  {
82  LOW = 0,
83  HIGH = 1,
84  BURST = 2,
85  MINIMAL = 3
86  } ShootHz;
87 
88  void heatCB(const rm_msgs::LocalHeatStateConstPtr& msg)
89  {
90  if (msg->has_shoot)
92  }
93 
94  void timerCB()
95  {
100  std_msgs::Float64 msg;
101  msg.data = local_shooter_cooling_heat_;
103  }
104 
105  void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
106  {
107  shooter_cooling_limit_ = data.shooter_cooling_limit;
108  shooter_cooling_rate_ = data.shooter_cooling_rate;
109  }
110 
111  void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
112  {
113  if (type_ == "ID1_17MM")
114  {
115  shooter_cooling_heat_ = data.shooter_id_1_17_mm_cooling_heat;
116  }
117  else if (type_ == "ID2_17MM")
118  {
119  shooter_cooling_heat_ = data.shooter_id_2_17_mm_cooling_heat;
120  }
121  else if (type_ == "ID1_42MM")
122  {
123  shooter_cooling_heat_ = data.shooter_id_1_42_mm_cooling_heat;
124  }
125  }
126 
127  void setRefereeStatus(bool status)
128  {
129  referee_is_online_ = status;
130  }
131 
132  double getShootFrequency() const
133  {
134  if (state_ == BURST)
135  return shoot_frequency_;
136  double shooter_cooling_heat =
138  if (shooter_cooling_limit_ - shooter_cooling_heat < bullet_heat_)
139  return 0.0;
140  else if (shooter_cooling_limit_ - shooter_cooling_heat == bullet_heat_)
142  else if (shooter_cooling_limit_ - shooter_cooling_heat <= bullet_heat_ * heat_coeff_)
143  return (shooter_cooling_limit_ - shooter_cooling_heat) / (bullet_heat_ * heat_coeff_) *
146  else
148  }
149 
151  {
153  if (type_ == "ID1_17MM")
154  return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
155  else if (type_ == "ID2_17MM")
156  return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
157  else if (type_ == "ID1_42MM")
158  return rm_msgs::ShootCmd::SPEED_16M_PER_SECOND;
159  return -1; // TODO unsafe!
160  }
161 
162  int getCoolingLimit()
163  {
164  return shooter_cooling_limit_;
165  }
166 
168  {
169  return shooter_cooling_heat_;
170  }
171 
172  void setShootFrequency(uint8_t mode)
173  {
174  state_ = mode;
175  }
176 
177  bool getShootFrequencyMode() const
178  {
179  return state_;
180  }
181 
182 private:
184  {
185  if (state_ == HeatLimit::BURST)
186  {
188  burst_flag_ = true;
189  }
190  else if (state_ == HeatLimit::LOW)
191  {
193  burst_flag_ = false;
194  }
195  else if (state_ == HeatLimit::HIGH)
196  {
198  burst_flag_ = false;
199  }
200  else if (state_ == HeatLimit::MINIMAL)
201  {
203  burst_flag_ = false;
204  }
205  else
206  {
208  burst_flag_ = false;
209  }
210  }
211 
212  uint8_t state_{};
213  std::string type_{};
214  bool burst_flag_ = false;
217 
221 
225 };
226 
227 } // namespace rm_common
rm_common::HeatLimit::shoot_frequency_
double shoot_frequency_
Definition: heat_limit.h:277
ros::Publisher
rm_common::HeatLimit::shooter_cooling_heat_
int shooter_cooling_heat_
Definition: heat_limit.h:281
rm_common::HeatLimit::getSpeedLimit
int getSpeedLimit()
Definition: heat_limit.h:212
rm_common::HeatLimit::shooter_cooling_limit_
int shooter_cooling_limit_
Definition: heat_limit.h:281
rm_common::HeatLimit::getCoolingLimit
int getCoolingLimit()
Definition: heat_limit.h:224
rm_common::HeatLimit::high_shoot_frequency_
double high_shoot_frequency_
Definition: heat_limit.h:278
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
rm_common::HeatLimit::use_local_heat_
bool use_local_heat_
Definition: heat_limit.h:280
rm_common::HeatLimit::burst_shoot_frequency_
double burst_shoot_frequency_
Definition: heat_limit.h:278
rm_common::HeatLimit::local_shooter_cooling_heat_
double local_shooter_cooling_heat_
Definition: heat_limit.h:282
rm_common::HeatLimit::HeatLimit
HeatLimit(ros::NodeHandle &nh)
Definition: heat_limit.h:114
rm_common::HeatLimit::heat_coeff_
double heat_coeff_
Definition: heat_limit.h:277
rm_common::HeatLimit::bullet_heat_
double bullet_heat_
Definition: heat_limit.h:277
rm_common::HeatLimit::getShootFrequency
double getShootFrequency() const
Definition: heat_limit.h:194
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rm_common::HeatLimit::heatCB
void heatCB(const rm_msgs::LocalHeatStateConstPtr &msg)
Definition: heat_limit.h:150
rm_common::HeatLimit::safe_shoot_frequency_
double safe_shoot_frequency_
Definition: heat_limit.h:277
rm_common::HeatLimit::setStatusOfShooter
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition: heat_limit.h:167
rm_common::HeatLimit::updateExpectShootFrequency
void updateExpectShootFrequency()
Definition: heat_limit.h:245
rm_common::HeatLimit::setRefereeStatus
void setRefereeStatus(bool status)
Definition: heat_limit.h:189
rm_common::HeatLimit::ShootHz
ShootHz
Definition: heat_limit.h:142
rm_common::HeatLimit::shooter_cooling_rate_
int shooter_cooling_rate_
Definition: heat_limit.h:281
rm_common::HeatLimit::setCoolingHeatOfShooter
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition: heat_limit.h:173
rm_common
Definition: calibration_queue.h:43
rm_common::HeatLimit::timerCB
void timerCB()
Definition: heat_limit.h:156
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rm_common::HeatLimit::low_shoot_frequency_
double low_shoot_frequency_
Definition: heat_limit.h:277
rm_common::HeatLimit::type_
std::string type_
Definition: heat_limit.h:275
rm_common::HeatLimit::setShootFrequency
void setShootFrequency(uint8_t mode)
Definition: heat_limit.h:234
rm_common::HeatLimit::shoot_state_sub_
ros::Subscriber shoot_state_sub_
Definition: heat_limit.h:285
rm_common::HeatLimit::getShootFrequencyMode
bool getShootFrequencyMode() const
Definition: heat_limit.h:239
rm_common::HeatLimit::timer_
ros::Timer timer_
Definition: heat_limit.h:286
rm_common::HeatLimit::local_heat_pub_
ros::Publisher local_heat_pub_
Definition: heat_limit.h:284
rm_common::HeatLimit::LOW
@ LOW
Definition: heat_limit.h:144
rm_common::HeatLimit::referee_is_online_
bool referee_is_online_
Definition: heat_limit.h:280
rm_common::HeatLimit::state_
uint8_t state_
Definition: heat_limit.h:274
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rm_common::HeatLimit::HIGH
@ HIGH
Definition: heat_limit.h:145
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
rm_common::HeatLimit::BURST
@ BURST
Definition: heat_limit.h:146
rm_common::HeatLimit::getCoolingHeat
int getCoolingHeat()
Definition: heat_limit.h:229
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
rm_common::HeatLimit::MINIMAL
@ MINIMAL
Definition: heat_limit.h:147
ros::Duration
ros::Timer
ros::NodeHandle
ros::Subscriber
rm_common::HeatLimit::minimal_shoot_frequency_
double minimal_shoot_frequency_
Definition: heat_limit.h:278
rm_common::HeatLimit::burst_flag_
bool burst_flag_
Definition: heat_limit.h:276


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01