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 
47 namespace rm_common
48 {
49 class PowerLimit
50 {
51 public:
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_)
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;
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  }
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  {
143  allow_gyro_cap_ = true;
145  allow_gyro_cap_ = false;
147  chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
148  else
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  {
160  {
162  chassis_cmd.power_limit = burst_power_;
163  else
164  {
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 
190 private:
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  {
211  {
212  if (is_gyro)
213  setGyroPower(chassis_cmd);
215  chassis_cmd.power_limit = burst_power_;
216  else
217  chassis_cmd.power_limit = standard_power_;
218  }
219  else
221  }
222 
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 };
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 
240  int total_burst_time_{};
241 
242  bool referee_is_online_{ false };
243  bool capacity_is_online_{ false };
244 };
245 } // namespace rm_common
rm_common::PowerLimit::normal
void normal(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:257
rm_common::PowerLimit::cap_state_
uint8_t cap_state_
Definition: power_limit.h:297
rm_common::PowerLimit::chassis_power_buffer_
int chassis_power_buffer_
Definition: power_limit.h:285
rm_common::PowerLimit::updateCapSwitchState
void updateCapSwitchState(bool state)
Definition: power_limit.h:166
rm_common::PowerLimit::extra_power_
double extra_power_
Definition: power_limit.h:293
rm_common::PowerLimit::disable_cap_gyro_threshold_
double disable_cap_gyro_threshold_
Definition: power_limit.h:292
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
rm_common::PowerLimit::max_power_limit_
int max_power_limit_
Definition: power_limit.h:287
rm_common::PowerLimit::capacitor_is_on_
bool capacitor_is_on_
Definition: power_limit.h:298
rm_common::PowerLimit::setLimitPower
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition: power_limit.h:213
rm_common::PowerLimit::expect_state_
uint8_t expect_state_
Definition: power_limit.h:297
rm_common::PowerLimit::updateState
void updateState(uint8_t state)
Definition: power_limit.h:159
rm_common::PowerLimit::PowerLimit
PowerLimit(ros::NodeHandle &nh)
Definition: power_limit.h:114
rm_common::PowerLimit::buffer_threshold_
double buffer_threshold_
Definition: power_limit.h:294
rm_common::PowerLimit::power_gain_
double power_gain_
Definition: power_limit.h:295
rm_common::PowerLimit::referee_is_online_
bool referee_is_online_
Definition: power_limit.h:304
rm_common::PowerLimit::getStartBurstTime
ros::Time getStartBurstTime() const
Definition: power_limit.h:194
rm_common::PowerLimit::standard_power_
double standard_power_
Definition: power_limit.h:293
rm_common::PowerLimit::setRefereeStatus
void setRefereeStatus(bool status)
Definition: power_limit.h:186
rm_common::PowerLimit::start_burst_time_
ros::Time start_burst_time_
Definition: power_limit.h:301
rm_common::PowerLimit::CHARGE
@ CHARGE
Definition: power_limit.h:146
rm_common::PowerLimit::total_burst_time_
int total_burst_time_
Definition: power_limit.h:302
rm_common::PowerLimit::robot_id_
int robot_id_
Definition: power_limit.h:286
rm_common::PowerLimit::getState
uint8_t getState()
Definition: power_limit.h:198
rm_common
Definition: calibration_queue.h:43
rm_common::PowerLimit::capacity_is_online_
bool capacity_is_online_
Definition: power_limit.h:305
rm_common::PowerLimit::charge
void charge(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:253
rm_common::PowerLimit::setGyroPower
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:202
rm_common::PowerLimit::Mode
Mode
Definition: power_limit.h:144
rm_common::PowerLimit::is_new_capacitor_
bool is_new_capacitor_
Definition: power_limit.h:296
rm_common::PowerLimit::enable_cap_gyro_threshold_
double enable_cap_gyro_threshold_
Definition: power_limit.h:292
rm_common::PowerLimit::allow_gyro_cap_
bool allow_gyro_cap_
Definition: power_limit.h:299
rm_common::PowerLimit::cap_energy_
float cap_energy_
Definition: power_limit.h:288
rm_common::PowerLimit::zero
void zero(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:266
rm_common::PowerLimit::safety_power_
double safety_power_
Definition: power_limit.h:289
rm_common::PowerLimit::chassis_power_limit_
int chassis_power_limit_
Definition: power_limit.h:286
ros::Time
rm_common::PowerLimit::charge_power_
double charge_power_
Definition: power_limit.h:293
rm_common::PowerLimit::setCapacityData
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition: power_limit.h:180
rm_common::PowerLimit::burst_power_
double burst_power_
Definition: power_limit.h:293
ROS_ERROR
#define ROS_ERROR(...)
rm_common::PowerLimit::setGameRobotData
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition: power_limit.h:170
rm_common::PowerLimit::NORMAL
@ NORMAL
Definition: power_limit.h:148
rm_common::PowerLimit::burst
void burst(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition: power_limit.h:270
rm_common::PowerLimit::capacitor_threshold_
double capacitor_threshold_
Definition: power_limit.h:290
rm_common::PowerLimit::TEST
@ TEST
Definition: power_limit.h:150
rm_common::PowerLimit::BURST
@ BURST
Definition: power_limit.h:147
rm_common::PowerLimit::updateSafetyPower
void updateSafetyPower(int safety_power)
Definition: power_limit.h:153
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ROS_INFO
#define ROS_INFO(...)
rm_common::PowerLimit::setChassisPowerBuffer
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition: power_limit.h:175
rm_common::PowerLimit::ALLOFF
@ ALLOFF
Definition: power_limit.h:149
ros::Duration
rm_common::PowerLimit::power_buffer_threshold_
double power_buffer_threshold_
Definition: power_limit.h:291
ros::NodeHandle
rm_common::PowerLimit::setStartBurstTime
void setStartBurstTime(const ros::Time start_burst_time)
Definition: power_limit.h:190
ros::Time::now
static Time now()


rm_common
Author(s):
autogenerated on Tue May 6 2025 02:23:36