rm_control
Loading...
Searching...
No Matches
power_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 bruce on 2021/7/28.
36//
37
38#pragma once
39
40#include <algorithm>
41#include <cmath>
42
43#include <ros/ros.h>
44#include <rm_msgs/ChassisCmd.h>
45#include <rm_msgs/GameStatus.h>
46#include <rm_msgs/GameRobotStatus.h>
47#include <rm_msgs/PowerHeatData.h>
48#include <rm_msgs/PowerManagementSampleAndStatusData.h>
49
50namespace rm_common
51{
53{
54public:
55 PowerLimit(ros::NodeHandle& nh)
56
57 {
58 if (!nh.getParam("safety_power", safety_power_))
59 ROS_ERROR("Safety power no defined (namespace: %s)", nh.getNamespace().c_str());
60 if (!nh.getParam("capacitor_threshold", capacitor_threshold_))
61 ROS_ERROR("Capacitor threshold no defined (namespace: %s)", nh.getNamespace().c_str());
62 if (!nh.getParam("disable_burst_cap_threshold", disable_burst_cap_threshold_))
63 ROS_ERROR("Disable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
64 if (!nh.getParam("enable_burst_cap_threshold", enable_burst_cap_threshold_))
65 ROS_ERROR("Enable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
66 if (!nh.getParam("disable_normal_cap_threshold", disable_normal_cap_threshold_))
67 ROS_ERROR("Disable normal cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
68 if (!nh.getParam("enable_gyro_cap_threshold", enable_gyro_cap_threshold_))
69 ROS_ERROR("Enable gyro cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
70 if (!nh.getParam("disable_gyro_cap_threshold", disable_gyro_cap_threshold_))
71 ROS_ERROR("Disable gyro cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
72 if (!nh.getParam("extra_power", extra_power_))
73 ROS_ERROR("Extra power no defined (namespace: %s)", nh.getNamespace().c_str());
74 if (!nh.getParam("burst_power", burst_power_))
75 ROS_ERROR("Burst power no defined (namespace: %s)", nh.getNamespace().c_str());
76 if (!nh.getParam("gyro_power", gyro_power_))
77 ROS_ERROR("Gyro power no defined (namespace: %s)", nh.getNamespace().c_str());
78 if (!nh.getParam("upstairs_power", upstairs_power_))
79 ROS_ERROR("Upstairs power no defined (namespace: %s)", nh.getNamespace().c_str());
80 if (!nh.getParam("max_power_limit", max_power_limit_))
81 ROS_ERROR("max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
82 if (!nh.getParam("power_gain", power_gain_))
83 ROS_ERROR("power gain no defined (namespace: %s)", nh.getNamespace().c_str());
84 if (!nh.getParam("total_burst_time", total_burst_time_))
85 ROS_ERROR("total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
86 default_max_power_limit_ = max_power_limit_;
87 default_burst_power_ = burst_power_;
88 }
89 typedef enum
90 {
91 CHARGE = 0,
92 BURST = 1,
93 NORMAL = 2,
94 ALLOFF = 3,
95 TEST = 4,
96 } Mode;
97
98 void updateSafetyPower(int safety_power)
99 {
100 if (safety_power > 0)
101 safety_power_ = safety_power;
102 ROS_INFO("update safety power: %d", safety_power);
103 }
104 void updateState(uint8_t state)
105 {
106 expect_state_ = state;
107 }
108 void setGameRobotData(const rm_msgs::GameRobotStatus data)
109 {
110 robot_id_ = data.robot_id;
111 chassis_power_limit_ = data.chassis_power_limit;
112 }
113 void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
114 {
115 chassis_power_buffer_ = data.chassis_power_buffer;
116 }
117 void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
118 {
119 capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
120 cap_energy_ = data.capacity_remain_charge;
121 cap_state_ = data.state_machine_running_state;
122 }
123 void setRefereeStatus(bool status)
124 {
125 referee_is_online_ = status;
126 }
127 void setStartBurstTime(const ros::Time start_burst_time)
128 {
129 start_burst_time_ = start_burst_time;
130 }
131 ros::Time getStartBurstTime() const
132 {
133 return start_burst_time_;
134 }
135 inline void setBurstPowerLimit(const double& burst_power_limit)
136 {
137 burst_power_ = burst_power_limit;
138 }
139 uint8_t getState()
140 {
141 return expect_state_;
142 }
143
144 void setUpstairsPower(bool upstairs)
145 {
146 if (upstairs)
147 {
148 max_power_limit_ = upstairs_power_;
149 burst_power_ = upstairs_power_;
150 }
151 else
152 {
153 max_power_limit_ = default_max_power_limit_;
154 burst_power_ = default_burst_power_;
155 }
156 }
157
158 void setGyroPower(rm_msgs::ChassisCmd& chassis_cmd)
159 {
160 if (!allow_gyro_cap_ && cap_energy_ >= enable_gyro_cap_threshold_)
161 allow_gyro_cap_ = true;
162 if (allow_gyro_cap_ && cap_energy_ <= disable_gyro_cap_threshold_)
163 allow_gyro_cap_ = false;
164 if (allow_gyro_cap_)
165 {
166 chassis_cmd.power_limit = gyro_power_;
167 }
168 else
169 expect_state_ = NORMAL;
170 }
171
172 void setBurstPower(rm_msgs::ChassisCmd& chassis_cmd)
173 {
174 if (!allow_use_cap_ && cap_energy_ >= enable_burst_cap_threshold_)
175 allow_use_cap_ = true;
176 if (allow_use_cap_ && cap_energy_ <= disable_burst_cap_threshold_)
177 allow_use_cap_ = false;
178 if (allow_use_cap_)
179 {
180 chassis_cmd.power_limit = burst_power_;
181 }
182 else
183 expect_state_ = NORMAL;
184 }
185
186 void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
187 {
188 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
189 chassis_cmd.power_limit = 400;
190 else
191 { // standard and hero
192 if (referee_is_online_)
193 {
194 if (capacity_is_online_ && expect_state_ != ALLOFF)
195 {
196 if (chassis_power_limit_ > burst_power_)
197 chassis_cmd.power_limit = burst_power_;
198 else
199 {
200 switch (expect_state_)
201 {
202 case NORMAL:
203 normal(chassis_cmd);
204 break;
205 case BURST:
206 burst(chassis_cmd, is_gyro);
207 break;
208 case CHARGE:
209 charge(chassis_cmd);
210 break;
211 default:
212 zero(chassis_cmd);
213 break;
214 }
215 }
216 }
217 else
218 normal(chassis_cmd);
219 }
220 else
221 chassis_cmd.power_limit = safety_power_;
222 }
223 applyPosturePowerScale(chassis_cmd);
224 }
225
226private:
227 void charge(rm_msgs::ChassisCmd& chassis_cmd)
228 {
229 allow_use_cap_ = false;
230 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
231 }
232
233 void normal(rm_msgs::ChassisCmd& chassis_cmd)
234 {
235 allow_use_cap_ = false;
236 if (cap_state_ != ALLOFF && cap_energy_ > disable_normal_cap_threshold_ &&
237 chassis_power_buffer_ > power_buffer_threshold_)
238 {
239 chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
240 }
241 else
242 {
243 chassis_cmd.power_limit = chassis_power_limit_;
244 }
245 if (chassis_cmd.power_limit > max_power_limit_)
246 {
247 chassis_cmd.power_limit = max_power_limit_;
248 }
249 }
250
251 void zero(rm_msgs::ChassisCmd& chassis_cmd)
252 {
253 chassis_cmd.power_limit = 0.0;
254 }
255
256 void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
257 {
258 if (cap_state_ != ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
259 {
260 if (is_gyro)
261 {
262 setGyroPower(chassis_cmd);
263 }
264 else
265 {
266 setBurstPower(chassis_cmd);
267 }
268 }
269 else
270 expect_state_ = NORMAL;
271 }
272
273 void applyPosturePowerScale(rm_msgs::ChassisCmd& chassis_cmd) const
274 {
275 if (std::abs(posture_power_scale_ - 1.0) < 1e-6)
276 return;
277 chassis_cmd.power_limit = std::max(0.0, std::floor(chassis_cmd.power_limit * posture_power_scale_));
278 }
279
280 uint8_t expect_state_{}, cap_state_{};
281
282 int chassis_power_buffer_{};
283 int robot_id_{}, chassis_power_limit_{};
284 double max_power_limit_{ 70.0 };
285 float cap_energy_{};
286 double safety_power_{};
287 double capacitor_threshold_{};
288 double power_buffer_threshold_{ 50.0 };
289 double enable_burst_cap_threshold_{}, disable_burst_cap_threshold_{};
290 double enable_gyro_cap_threshold_{}, disable_gyro_cap_threshold_{};
291 double disable_normal_cap_threshold_{};
292 double extra_power_{}, burst_power_{}, gyro_power_{}, upstairs_power_{};
293 double default_max_power_limit_{}, default_burst_power_{};
294 double power_gain_{};
295
296 bool allow_gyro_cap_{ false }, allow_use_cap_{ false };
297 double posture_power_scale_{ 1.0 };
298
299 ros::Time start_burst_time_{};
300 int total_burst_time_{};
301
302 bool referee_is_online_{ false };
303 bool capacity_is_online_{ false };
304};
305} // namespace rm_common
Definition power_limit.h:53
PowerLimit(ros::NodeHandle &nh)
Definition power_limit.h:55
void updateState(uint8_t state)
Definition power_limit.h:104
void setRefereeStatus(bool status)
Definition power_limit.h:123
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:117
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:113
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:108
Mode
Definition power_limit.h:90
@ BURST
Definition power_limit.h:92
@ ALLOFF
Definition power_limit.h:94
@ CHARGE
Definition power_limit.h:91
@ NORMAL
Definition power_limit.h:93
@ TEST
Definition power_limit.h:95
void setUpstairsPower(bool upstairs)
Definition power_limit.h:144
ros::Time getStartBurstTime() const
Definition power_limit.h:131
void setBurstPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:172
uint8_t getState()
Definition power_limit.h:139
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:186
void setStartBurstTime(const ros::Time start_burst_time)
Definition power_limit.h:127
void setBurstPowerLimit(const double &burst_power_limit)
Definition power_limit.h:135
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:158
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition calibration_queue.h:44