rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
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("charge_power", charge_power_))
64 ROS_ERROR("Charge power no defined (namespace: %s)", nh.getNamespace().c_str());
65 if (!nh.getParam("extra_power", extra_power_))
66 ROS_ERROR("Extra power no defined (namespace: %s)", nh.getNamespace().c_str());
67 if (!nh.getParam("burst_power", burst_power_))
68 ROS_ERROR("Burst power no defined (namespace: %s)", nh.getNamespace().c_str());
69 if (!nh.getParam("standard_power", standard_power_))
70 ROS_ERROR("Standard power no defined (namespace: %s)", nh.getNamespace().c_str());
71 if (!nh.getParam("max_power_limit", max_power_limit_))
72 ROS_ERROR("max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
73 if (!nh.getParam("power_gain", power_gain_))
74 ROS_ERROR("power gain no defined (namespace: %s)", nh.getNamespace().c_str());
75 if (!nh.getParam("buffer_threshold", buffer_threshold_))
76 ROS_ERROR("buffer threshold no defined (namespace: %s)", nh.getNamespace().c_str());
77 if (!nh.getParam("is_new_capacitor", is_new_capacitor_))
78 ROS_ERROR("is_new_capacitor no defined (namespace: %s)", nh.getNamespace().c_str());
79 if (!nh.getParam("total_burst_time", total_burst_time_))
80 ROS_ERROR("total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
81 }
82 typedef enum
83 {
84 CHARGE = 0,
85 BURST = 1,
86 NORMAL = 2,
87 ALLOFF = 3,
88 TEST = 4,
89 } Mode;
90
91 void updateSafetyPower(int safety_power)
92 {
93 if (safety_power > 0)
94 safety_power_ = safety_power;
95 ROS_INFO("update safety power: %d", safety_power);
96 }
97 void updateState(uint8_t state)
98 {
99 if (!capacitor_is_on_)
100 expect_state_ = ALLOFF;
101 else
102 expect_state_ = state;
103 }
104 void updateCapSwitchState(bool state)
105 {
106 capacitor_is_on_ = 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 power_buffer_threshold_ = chassis_power_buffer_ * 0.8;
117 }
118 void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
119 {
120 capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
121 cap_energy_ = data.capacity_remain_charge;
122 cap_state_ = data.state_machine_running_state;
123 }
124 void setRefereeStatus(bool status)
125 {
126 referee_is_online_ = status;
127 }
128 void setStartBurstTime(const ros::Time start_burst_time)
129 {
130 start_burst_time_ = start_burst_time;
131 }
132 ros::Time getStartBurstTime() const
133 {
134 return start_burst_time_;
135 }
136 uint8_t getState()
137 {
138 return expect_state_;
139 }
140 void setGyroPower(rm_msgs::ChassisCmd& chassis_cmd)
141 {
142 if (!allow_gyro_cap_ && cap_energy_ >= enable_cap_gyro_threshold_)
143 allow_gyro_cap_ = true;
144 if (allow_gyro_cap_ && cap_energy_ <= disable_cap_gyro_threshold_)
145 allow_gyro_cap_ = false;
146 if (allow_gyro_cap_ && chassis_power_limit_ < 80)
147 chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
148 else
149 expect_state_ = NORMAL;
150 }
151 void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
152 {
153 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
154 chassis_cmd.power_limit = 400;
155 else
156 { // standard and hero
157 if (referee_is_online_)
158 {
159 if (capacity_is_online_ && expect_state_ != ALLOFF)
160 {
161 if (chassis_power_limit_ > burst_power_)
162 chassis_cmd.power_limit = burst_power_;
163 else
164 {
165 switch (is_new_capacitor_ ? expect_state_ : cap_state_)
166 {
167 case NORMAL:
168 normal(chassis_cmd);
169 break;
170 case BURST:
171 burst(chassis_cmd, is_gyro);
172 break;
173 case CHARGE:
174 charge(chassis_cmd);
175 break;
176 default:
177 zero(chassis_cmd);
178 break;
179 }
180 }
181 }
182 else
183 normal(chassis_cmd);
184 }
185 else
186 chassis_cmd.power_limit = safety_power_;
187 }
188 }
189
190private:
191 void charge(rm_msgs::ChassisCmd& chassis_cmd)
192 {
193 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
194 }
195 void normal(rm_msgs::ChassisCmd& chassis_cmd)
196 {
197 double buffer_energy_error = chassis_power_buffer_ - buffer_threshold_;
198 double plus_power = buffer_energy_error * power_gain_;
199 chassis_cmd.power_limit = chassis_power_limit_ + plus_power;
200 // TODO:Add protection when buffer<5
201 if (chassis_cmd.power_limit > max_power_limit_)
202 chassis_cmd.power_limit = max_power_limit_;
203 }
204 void zero(rm_msgs::ChassisCmd& chassis_cmd)
205 {
206 chassis_cmd.power_limit = 0.0;
207 }
208 void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
209 {
210 if (cap_state_ != ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
211 {
212 if (is_gyro)
213 setGyroPower(chassis_cmd);
214 else if (ros::Time::now() - start_burst_time_ < ros::Duration(total_burst_time_))
215 chassis_cmd.power_limit = burst_power_;
216 else
217 chassis_cmd.power_limit = standard_power_;
218 }
219 else
220 expect_state_ = NORMAL;
221 }
222
223 int chassis_power_buffer_;
224 int robot_id_, chassis_power_limit_;
225 int max_power_limit_{ 70 };
226 float cap_energy_;
227 double safety_power_{};
228 double capacitor_threshold_{};
229 double power_buffer_threshold_{ 50.0 };
230 double enable_cap_gyro_threshold_{}, disable_cap_gyro_threshold_{};
231 double charge_power_{}, extra_power_{}, burst_power_{}, standard_power_{};
232 double buffer_threshold_{};
233 double power_gain_{};
234 bool is_new_capacitor_{ false };
235 uint8_t expect_state_{}, cap_state_{};
236 bool capacitor_is_on_{ true };
237 bool allow_gyro_cap_{ false };
238
239 ros::Time start_burst_time_{};
240 int total_burst_time_{};
241
242 bool referee_is_online_{ false };
243 bool capacity_is_online_{ false };
244};
245} // 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:97
void setRefereeStatus(bool status)
Definition power_limit.h:124
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:118
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:83
@ BURST
Definition power_limit.h:85
@ ALLOFF
Definition power_limit.h:87
@ CHARGE
Definition power_limit.h:84
@ NORMAL
Definition power_limit.h:86
@ TEST
Definition power_limit.h:88
ros::Time getStartBurstTime() const
Definition power_limit.h:132
uint8_t getState()
Definition power_limit.h:136
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:151
void updateCapSwitchState(bool state)
Definition power_limit.h:104
void setStartBurstTime(const ros::Time start_burst_time)
Definition power_limit.h:128
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:140
void updateSafetyPower(int safety_power)
Definition power_limit.h:91
Definition calibration_queue.h:44