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 <ros/ros.h>
41#include <rm_msgs/ChassisCmd.h>
42#include <rm_msgs/GameStatus.h>
43#include <rm_msgs/GameRobotStatus.h>
44#include <rm_msgs/PowerHeatData.h>
45#include <rm_msgs/PowerManagementSampleAndStatusData.h>
46
47namespace rm_common
48{
50{
51public:
52 PowerLimit(ros::NodeHandle& nh)
53
54 {
55 if (!nh.getParam("safety_power", safety_power_))
56 ROS_ERROR("Safety power no defined (namespace: %s)", nh.getNamespace().c_str());
57 if (!nh.getParam("capacitor_threshold", capacitor_threshold_))
58 ROS_ERROR("Capacitor threshold no defined (namespace: %s)", nh.getNamespace().c_str());
59 if (!nh.getParam("disable_cap_gyro_threshold", disable_cap_gyro_threshold_))
60 ROS_ERROR("Disable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
61 if (!nh.getParam("enable_cap_gyro_threshold", enable_cap_gyro_threshold_))
62 ROS_ERROR("Enable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
63 if (!nh.getParam("disable_use_cap_threshold", disable_use_cap_threshold_))
64 ROS_ERROR("Disable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
65 if (!nh.getParam("enable_use_cap_threshold", enable_use_cap_threshold_))
66 ROS_ERROR("Enable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
67 if (!nh.getParam("charge_power", charge_power_))
68 ROS_ERROR("Charge power no defined (namespace: %s)", nh.getNamespace().c_str());
69 if (!nh.getParam("extra_power", extra_power_))
70 ROS_ERROR("Extra power no defined (namespace: %s)", nh.getNamespace().c_str());
71 if (!nh.getParam("burst_power", burst_power_))
72 ROS_ERROR("Burst power no defined (namespace: %s)", nh.getNamespace().c_str());
73 if (!nh.getParam("standard_power", standard_power_))
74 ROS_ERROR("Standard power no defined (namespace: %s)", nh.getNamespace().c_str());
75 if (!nh.getParam("max_power_limit", max_power_limit_))
76 ROS_ERROR("max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
77 if (!nh.getParam("power_gain", power_gain_))
78 ROS_ERROR("power gain no defined (namespace: %s)", nh.getNamespace().c_str());
79 if (!nh.getParam("buffer_threshold", buffer_threshold_))
80 ROS_ERROR("buffer threshold no defined (namespace: %s)", nh.getNamespace().c_str());
81 if (!nh.getParam("is_new_capacitor", is_new_capacitor_))
82 ROS_ERROR("is_new_capacitor no defined (namespace: %s)", nh.getNamespace().c_str());
83 if (!nh.getParam("total_burst_time", total_burst_time_))
84 ROS_ERROR("total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
85 }
86 typedef enum
87 {
88 CHARGE = 0,
89 BURST = 1,
90 NORMAL = 2,
91 ALLOFF = 3,
92 TEST = 4,
93 } Mode;
94
95 void updateSafetyPower(int safety_power)
96 {
97 if (safety_power > 0)
98 safety_power_ = safety_power;
99 ROS_INFO("update safety power: %d", safety_power);
100 }
101 void updateState(uint8_t state)
102 {
103 if (!capacitor_is_on_)
104 expect_state_ = ALLOFF;
105 else
106 expect_state_ = state;
107 }
108 void updateCapSwitchState(bool state)
109 {
110 capacitor_is_on_ = state;
111 }
112 void setGameRobotData(const rm_msgs::GameRobotStatus data)
113 {
114 robot_id_ = data.robot_id;
115 chassis_power_limit_ = data.chassis_power_limit;
116 }
117 void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
118 {
119 chassis_power_buffer_ = data.chassis_power_buffer;
120 power_buffer_threshold_ = chassis_power_buffer_ * 0.8;
121 }
122 void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
123 {
124 capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
125 cap_energy_ = data.capacity_remain_charge;
126 cap_state_ = data.state_machine_running_state;
127 }
128 void setRefereeStatus(bool status)
129 {
130 referee_is_online_ = status;
131 }
132 void setStartBurstTime(const ros::Time start_burst_time)
133 {
134 start_burst_time_ = start_burst_time;
135 }
136 ros::Time getStartBurstTime() const
137 {
138 return start_burst_time_;
139 }
140 uint8_t getState()
141 {
142 return expect_state_;
143 }
144 void setGyroPower(rm_msgs::ChassisCmd& chassis_cmd)
145 {
146 if (!allow_gyro_cap_ && cap_energy_ >= enable_cap_gyro_threshold_)
147 allow_gyro_cap_ = true;
148 if (allow_gyro_cap_ && cap_energy_ <= disable_cap_gyro_threshold_)
149 allow_gyro_cap_ = false;
150 if (allow_gyro_cap_ && chassis_power_limit_ < 80)
151 chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
152 else
153 normal(chassis_cmd);
154 // expect_state_ = NORMAL;
155 }
156 void setBurstPower(rm_msgs::ChassisCmd& chassis_cmd)
157 {
158 if (!allow_use_cap_ && cap_energy_ >= enable_use_cap_threshold_)
159 allow_use_cap_ = true;
160 if (allow_use_cap_ && cap_energy_ <= disable_use_cap_threshold_)
161 allow_use_cap_ = false;
162 if (allow_use_cap_)
163 {
164 if (ros::Time::now() - start_burst_time_ < ros::Duration(total_burst_time_))
165 chassis_cmd.power_limit = burst_power_;
166 else
167 chassis_cmd.power_limit = standard_power_;
168 }
169 else
170 normal(chassis_cmd);
171 // expect_state_ = NORMAL;
172 }
173 void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
174 {
175 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
176 chassis_cmd.power_limit = 400;
177 else
178 { // standard and hero
179 if (referee_is_online_)
180 {
181 if (capacity_is_online_ && expect_state_ != ALLOFF)
182 {
183 if (chassis_power_limit_ > burst_power_)
184 chassis_cmd.power_limit = burst_power_;
185 else
186 {
187 switch (is_new_capacitor_ ? expect_state_ : cap_state_)
188 {
189 case NORMAL:
190 normal(chassis_cmd);
191 break;
192 case BURST:
193 burst(chassis_cmd, is_gyro);
194 break;
195 case CHARGE:
196 charge(chassis_cmd);
197 break;
198 default:
199 zero(chassis_cmd);
200 break;
201 }
202 }
203 }
204 else
205 normal(chassis_cmd);
206 }
207 else
208 chassis_cmd.power_limit = safety_power_;
209 }
210 }
211
212private:
213 void charge(rm_msgs::ChassisCmd& chassis_cmd)
214 {
215 allow_use_cap_ = false;
216 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
217 }
218 void normal(rm_msgs::ChassisCmd& chassis_cmd)
219 {
220 allow_use_cap_ = false;
221 double buffer_energy_error = chassis_power_buffer_ - buffer_threshold_;
222 double plus_power = buffer_energy_error * power_gain_;
223 chassis_cmd.power_limit = chassis_power_limit_ + plus_power;
224 // TODO:Add protection when buffer<5
225 if (chassis_cmd.power_limit > max_power_limit_)
226 chassis_cmd.power_limit = max_power_limit_;
227 }
228 void zero(rm_msgs::ChassisCmd& chassis_cmd)
229 {
230 chassis_cmd.power_limit = 0.0;
231 }
232 void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
233 {
234 if (cap_state_ != ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
235 {
236 if (is_gyro)
237 setGyroPower(chassis_cmd);
238 else
239 setBurstPower(chassis_cmd);
240 }
241 else
242 normal(chassis_cmd);
243 // expect_state_ = NORMAL;
244 }
245
246 int chassis_power_buffer_;
247 int robot_id_, chassis_power_limit_;
248 int max_power_limit_{ 70 };
249 float cap_energy_;
250 double safety_power_{};
251 double capacitor_threshold_{};
252 double power_buffer_threshold_{ 50.0 };
253 double enable_cap_gyro_threshold_{}, disable_cap_gyro_threshold_{}, enable_use_cap_threshold_{},
254 disable_use_cap_threshold_{};
255 double charge_power_{}, extra_power_{}, burst_power_{}, standard_power_{};
256 double buffer_threshold_{};
257 double power_gain_{};
258 bool is_new_capacitor_{ false };
259 uint8_t expect_state_{}, cap_state_{};
260 bool capacitor_is_on_{ true };
261 bool allow_gyro_cap_{ false }, allow_use_cap_{ false };
262
263 ros::Time start_burst_time_{};
264 int total_burst_time_{};
265
266 bool referee_is_online_{ false };
267 bool capacity_is_online_{ false };
268};
269} // namespace rm_common
Definition power_limit.h:50
PowerLimit(ros::NodeHandle &nh)
Definition power_limit.h:52
void updateState(uint8_t state)
Definition power_limit.h:101
void setRefereeStatus(bool status)
Definition power_limit.h:128
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:122
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:117
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:112
Mode
Definition power_limit.h:87
@ BURST
Definition power_limit.h:89
@ ALLOFF
Definition power_limit.h:91
@ CHARGE
Definition power_limit.h:88
@ NORMAL
Definition power_limit.h:90
@ TEST
Definition power_limit.h:92
ros::Time getStartBurstTime() const
Definition power_limit.h:136
void setBurstPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:156
uint8_t getState()
Definition power_limit.h:140
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:173
void updateCapSwitchState(bool state)
Definition power_limit.h:108
void setStartBurstTime(const ros::Time start_burst_time)
Definition power_limit.h:132
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:144
void updateSafetyPower(int safety_power)
Definition power_limit.h:95
Definition calibration_queue.h:44