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("charge_power", charge_power_))
60  ROS_ERROR("Charge power no defined (namespace: %s)", nh.getNamespace().c_str());
61  if (!nh.getParam("extra_power", extra_power_))
62  ROS_ERROR("Extra power no defined (namespace: %s)", nh.getNamespace().c_str());
63  if (!nh.getParam("burst_power", burst_power_))
64  ROS_ERROR("Burst power no defined (namespace: %s)", nh.getNamespace().c_str());
65  if (!nh.getParam("power_gain", power_gain_))
66  ROS_ERROR("power gain no defined (namespace: %s)", nh.getNamespace().c_str());
67  if (!nh.getParam("buffer_threshold", buffer_threshold_))
68  ROS_ERROR("buffer threshold no defined (namespace: %s)", nh.getNamespace().c_str());
69  if (!nh.getParam("is_new_capacitor", is_new_capacitor_))
70  ROS_ERROR("is_new_capacitor no defined (namespace: %s)", nh.getNamespace().c_str());
71  }
72  typedef enum
73  {
74  CHARGE = 0,
75  BURST = 1,
76  NORMAL = 2,
77  ALLOFF = 3,
78  TEST = 4,
79  } Mode;
80 
81  void updateSafetyPower(int safety_power)
82  {
83  if (safety_power > 0)
84  safety_power_ = safety_power;
85  ROS_INFO("update safety power: %d", safety_power);
86  }
87  void updateState(uint8_t state)
88  {
89  if (!capacitor_is_on_)
91  else
92  expect_state_ = state;
93  }
94  void updateCapSwitchState(bool state)
95  {
96  capacitor_is_on_ = state;
97  }
98  void setGameRobotData(const rm_msgs::GameRobotStatus data)
99  {
100  robot_id_ = data.robot_id;
101  chassis_power_limit_ = data.chassis_power_limit;
102  }
103  void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
104  {
105  chassis_power_buffer_ = data.chassis_power_buffer;
106  }
107  void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
108  {
109  capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
110  cap_energy_ = data.capacity_remain_charge;
111  cap_state_ = data.state_machine_running_state;
112  }
113  void setRefereeStatus(bool status)
114  {
115  referee_is_online_ = status;
116  }
117 
118  uint8_t getState()
119  {
120  return expect_state_;
121  }
122  void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
123  {
124  if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
125  chassis_cmd.power_limit = 400;
126  else
127  { // standard and hero
128  if (referee_is_online_)
129  {
131  {
132  if (expect_state_ == ALLOFF)
133  normal(chassis_cmd);
134  else
135  {
137  chassis_cmd.power_limit = burst_power_;
138  else
139  {
141  {
142  case NORMAL:
143  normal(chassis_cmd);
144  break;
145  case BURST:
146  burst(chassis_cmd, is_gyro);
147  break;
148  case CHARGE:
149  charge(chassis_cmd);
150  break;
151  default:
152  zero(chassis_cmd);
153  break;
154  }
155  }
156  }
157  }
158  else
159  normal(chassis_cmd);
160  }
161  else
162  chassis_cmd.power_limit = safety_power_;
163  }
164  }
165 
166 private:
167  void charge(rm_msgs::ChassisCmd& chassis_cmd)
168  {
169  chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
170  }
171  void normal(rm_msgs::ChassisCmd& chassis_cmd)
172  {
173  double buffer_energy_error = chassis_power_buffer_ - buffer_threshold_;
174  double plus_power = buffer_energy_error * power_gain_;
175  chassis_cmd.power_limit = chassis_power_limit_ + plus_power;
176  // TODO:Add protection when buffer<5
177  }
178  void zero(rm_msgs::ChassisCmd& chassis_cmd)
179  {
180  chassis_cmd.power_limit = 0.0;
181  }
182  void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
183  {
185  {
186  if (is_gyro)
187  chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
188  else
189  chassis_cmd.power_limit = burst_power_;
190  }
191  else
193  }
194 
197  float cap_energy_;
198  double safety_power_{};
199  double capacitor_threshold_{};
200  double charge_power_{}, extra_power_{}, burst_power_{};
201  double buffer_threshold_{};
202  double power_gain_{};
203  bool is_new_capacitor_{ false };
204  uint8_t expect_state_{}, cap_state_{};
205  bool capacitor_is_on_{ true };
206 
207  bool referee_is_online_{ false };
208  bool capacity_is_online_{ false };
209 };
210 } // namespace rm_common
rm_common::PowerLimit::normal
void normal(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:233
rm_common::PowerLimit::cap_state_
uint8_t cap_state_
Definition: power_limit.h:266
rm_common::PowerLimit::chassis_power_buffer_
int chassis_power_buffer_
Definition: power_limit.h:257
rm_common::PowerLimit::updateCapSwitchState
void updateCapSwitchState(bool state)
Definition: power_limit.h:156
rm_common::PowerLimit::extra_power_
double extra_power_
Definition: power_limit.h:262
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
rm_common::PowerLimit::capacitor_is_on_
bool capacitor_is_on_
Definition: power_limit.h:267
rm_common::PowerLimit::setLimitPower
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition: power_limit.h:184
rm_common::PowerLimit::expect_state_
uint8_t expect_state_
Definition: power_limit.h:266
rm_common::PowerLimit::updateState
void updateState(uint8_t state)
Definition: power_limit.h:149
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:263
rm_common::PowerLimit::power_gain_
double power_gain_
Definition: power_limit.h:264
rm_common::PowerLimit::referee_is_online_
bool referee_is_online_
Definition: power_limit.h:269
rm_common::PowerLimit::setRefereeStatus
void setRefereeStatus(bool status)
Definition: power_limit.h:175
rm_common::PowerLimit::CHARGE
@ CHARGE
Definition: power_limit.h:136
rm_common::PowerLimit::robot_id_
int robot_id_
Definition: power_limit.h:258
rm_common::PowerLimit::getState
uint8_t getState()
Definition: power_limit.h:180
rm_common
Definition: calibration_queue.h:43
rm_common::PowerLimit::capacity_is_online_
bool capacity_is_online_
Definition: power_limit.h:270
rm_common::PowerLimit::charge
void charge(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:229
rm_common::PowerLimit::Mode
Mode
Definition: power_limit.h:134
rm_common::PowerLimit::is_new_capacitor_
bool is_new_capacitor_
Definition: power_limit.h:265
rm_common::PowerLimit::cap_energy_
float cap_energy_
Definition: power_limit.h:259
rm_common::PowerLimit::zero
void zero(rm_msgs::ChassisCmd &chassis_cmd)
Definition: power_limit.h:240
rm_common::PowerLimit::safety_power_
double safety_power_
Definition: power_limit.h:260
rm_common::PowerLimit::chassis_power_limit_
int chassis_power_limit_
Definition: power_limit.h:258
rm_common::PowerLimit::charge_power_
double charge_power_
Definition: power_limit.h:262
rm_common::PowerLimit::setCapacityData
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition: power_limit.h:169
rm_common::PowerLimit::burst_power_
double burst_power_
Definition: power_limit.h:262
ROS_ERROR
#define ROS_ERROR(...)
rm_common::PowerLimit::setGameRobotData
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition: power_limit.h:160
rm_common::PowerLimit::NORMAL
@ NORMAL
Definition: power_limit.h:138
rm_common::PowerLimit::burst
void burst(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition: power_limit.h:244
rm_common::PowerLimit::capacitor_threshold_
double capacitor_threshold_
Definition: power_limit.h:261
rm_common::PowerLimit::TEST
@ TEST
Definition: power_limit.h:140
rm_common::PowerLimit::BURST
@ BURST
Definition: power_limit.h:137
rm_common::PowerLimit::updateSafetyPower
void updateSafetyPower(int safety_power)
Definition: power_limit.h:143
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:165
rm_common::PowerLimit::ALLOFF
@ ALLOFF
Definition: power_limit.h:139
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01