@@ -45,13 +45,9 @@ class HeatLimit
4545public:
4646 HeatLimit (ros::NodeHandle& nh, const RefereeData& referee_data) : referee_data_(referee_data)
4747 {
48- if (!nh.getParam (" expect_shoot_frequency_1 " , expect_shoot_frequency_1_ ))
48+ if (!nh.getParam (" low_shoot_frequency " , low_shoot_frequency_ ))
4949 ROS_ERROR (" Expect shoot frequency no defined (namespace: %s)" , nh.getNamespace ().c_str ());
50- if (!nh.getParam (" expect_shoot_frequency_2" , expect_shoot_frequency_2_))
51- ROS_ERROR (" Expect shoot frequency no defined (namespace: %s)" , nh.getNamespace ().c_str ());
52- if (!nh.getParam (" expect_shoot_frequency_3" , expect_shoot_frequency_3_))
53- ROS_ERROR (" Expect shoot frequency no defined (namespace: %s)" , nh.getNamespace ().c_str ());
54- if (!nh.getParam (" burst_shoot_frequency" , burst_shoot_frequency_))
50+ if (!nh.getParam (" high_shoot_frequency" , high_shoot_frequency_))
5551 ROS_ERROR (" Expect shoot frequency no defined (namespace: %s)" , nh.getNamespace ().c_str ());
5652 if (!nh.getParam (" safe_shoot_frequency" , safe_shoot_frequency_))
5753 ROS_ERROR (" Safe shoot frequency no defined (namespace: %s)" , nh.getNamespace ().c_str ());
@@ -65,9 +61,16 @@ class HeatLimit
6561 bullet_heat_ = 10 .;
6662 }
6763
68- double getHz () const
64+ typedef enum
65+ {
66+ LOW = 0 ,
67+ HIGH = 1 ,
68+ BURST = 2 ,
69+ } ShootHz;
70+
71+ double getShootFrequency () const
6972 {
70- if (burst_flag_ )
73+ if (state_ == BURST )
7174 return shoot_frequency_;
7275 if (!referee_data_.is_online_ )
7376 return safe_shoot_frequency_;
@@ -143,34 +146,34 @@ class HeatLimit
143146 return -1 ; // TODO unsafe!
144147 }
145148
146- void updateExpectShootFrequency ( )
149+ void setShootFrequency ( uint8_t mode )
147150 {
148- if (burst_flag_)
149- shoot_frequency_ = burst_shoot_frequency_;
150- else if (referee_data_.game_robot_status_ .robot_level_ == 1 )
151- shoot_frequency_ = expect_shoot_frequency_1_;
152- else if (referee_data_.game_robot_status_ .robot_level_ == 2 )
153- shoot_frequency_ = expect_shoot_frequency_2_;
154- else if (referee_data_.game_robot_status_ .robot_level_ == 3 )
155- shoot_frequency_ = expect_shoot_frequency_3_;
156- else
157- shoot_frequency_ = safe_shoot_frequency_;
151+ state_ = mode;
158152 }
159153
160- void setMode ( bool burst_flag)
154+ bool getShootFrequencyMode () const
161155 {
162- burst_flag_ = burst_flag ;
156+ return state_ ;
163157 }
164- bool getMode () const
158+
159+ private:
160+ void updateExpectShootFrequency ()
165161 {
166- return burst_flag_;
162+ if (state_ == HeatLimit::BURST)
163+ shoot_frequency_ = high_shoot_frequency_;
164+ else if (state_ == HeatLimit::LOW)
165+ shoot_frequency_ = low_shoot_frequency_;
166+ else if (state_ == HeatLimit::HIGH)
167+ shoot_frequency_ = high_shoot_frequency_;
168+ else
169+ shoot_frequency_ = safe_shoot_frequency_;
167170 }
168171
169- private:
170172 std::string type_{};
171173 const RefereeData& referee_data_;
172- double bullet_heat_, safe_shoot_frequency_{}, heat_coeff_{}, shoot_frequency_{}, expect_shoot_frequency_1_{},
173- expect_shoot_frequency_2_{}, expect_shoot_frequency_3_{}, burst_shoot_frequency_{};
174+ double bullet_heat_, safe_shoot_frequency_{}, heat_coeff_{}, shoot_frequency_{}, low_shoot_frequency_{},
175+ high_shoot_frequency_{};
176+ uint8_t state_{};
174177 bool burst_flag_ = false ;
175178};
176179
0 commit comments