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>
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_cap_gyro_threshold", disable_cap_gyro_threshold_))
63 ROS_ERROR(
"Disable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
64 if (!nh.getParam(
"enable_cap_gyro_threshold", enable_cap_gyro_threshold_))
65 ROS_ERROR(
"Enable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
66 if (!nh.getParam(
"disable_use_cap_threshold", disable_use_cap_threshold_))
67 ROS_ERROR(
"Disable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
68 if (!nh.getParam(
"enable_use_cap_threshold", enable_use_cap_threshold_))
69 ROS_ERROR(
"Enable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
70 if (!nh.getParam(
"charge_power", charge_power_))
71 ROS_ERROR(
"Charge power 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(
"standard_power", standard_power_))
77 ROS_ERROR(
"Standard power no defined (namespace: %s)", nh.getNamespace().c_str());
78 if (!nh.getParam(
"max_power_limit", max_power_limit_))
79 ROS_ERROR(
"max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
80 if (!nh.getParam(
"power_gain", power_gain_))
81 ROS_ERROR(
"power gain no defined (namespace: %s)", nh.getNamespace().c_str());
82 if (!nh.getParam(
"buffer_threshold", buffer_threshold_))
83 ROS_ERROR(
"buffer threshold no defined (namespace: %s)", nh.getNamespace().c_str());
84 if (!nh.getParam(
"is_new_capacitor", is_new_capacitor_))
85 ROS_ERROR(
"is_new_capacitor no defined (namespace: %s)", nh.getNamespace().c_str());
86 if (!nh.getParam(
"total_burst_time", total_burst_time_))
87 ROS_ERROR(
"total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
100 if (safety_power > 0)
101 safety_power_ = safety_power;
102 ROS_INFO(
"update safety power: %d", safety_power);
106 if (!capacitor_is_on_)
109 expect_state_ = state;
113 capacitor_is_on_ = state;
117 robot_id_ = data.robot_id;
118 chassis_power_limit_ = data.chassis_power_limit;
122 chassis_power_buffer_ = data.chassis_power_buffer;
123 power_buffer_threshold_ = chassis_power_buffer_ * 0.8;
127 capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
128 cap_energy_ = data.capacity_remain_charge;
129 cap_state_ = data.state_machine_running_state;
133 referee_is_online_ = status;
137 start_burst_time_ = start_burst_time;
141 burst_power_ = burst_power_limit;
145 return start_burst_time_;
149 return expect_state_;
153 if (!allow_gyro_cap_ && cap_energy_ >= enable_cap_gyro_threshold_)
154 allow_gyro_cap_ =
true;
155 if (allow_gyro_cap_ && cap_energy_ <= disable_cap_gyro_threshold_)
156 allow_gyro_cap_ =
false;
157 if (allow_gyro_cap_ && chassis_power_limit_ < 80)
158 chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
165 if (!allow_use_cap_ && cap_energy_ >= enable_use_cap_threshold_)
166 allow_use_cap_ =
true;
167 if (allow_use_cap_ && cap_energy_ <= disable_use_cap_threshold_)
168 allow_use_cap_ =
false;
171 if (ros::Time::now() - start_burst_time_ < ros::Duration(total_burst_time_))
172 chassis_cmd.power_limit = burst_power_;
174 chassis_cmd.power_limit = standard_power_;
182 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
183 chassis_cmd.power_limit = 400;
186 if (referee_is_online_)
188 if (capacity_is_online_ && expect_state_ !=
ALLOFF)
190 if (chassis_power_limit_ > burst_power_)
191 chassis_cmd.power_limit = burst_power_;
194 switch (is_new_capacitor_ ? expect_state_ : cap_state_)
200 burst(chassis_cmd, is_gyro);
215 chassis_cmd.power_limit = safety_power_;
217 applyPosturePowerScale(chassis_cmd);
221 void charge(rm_msgs::ChassisCmd& chassis_cmd)
223 allow_use_cap_ =
false;
224 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
226 void normal(rm_msgs::ChassisCmd& chassis_cmd)
228 if (is_new_capacitor_)
230 chassis_cmd.power_limit = chassis_power_limit_;
233 allow_use_cap_ =
false;
234 double buffer_energy_error = chassis_power_buffer_ - buffer_threshold_;
235 double plus_power = buffer_energy_error * power_gain_;
236 chassis_cmd.power_limit = chassis_power_limit_ + plus_power;
238 if (chassis_cmd.power_limit > max_power_limit_)
239 chassis_cmd.power_limit = max_power_limit_;
241 void zero(rm_msgs::ChassisCmd& chassis_cmd)
243 chassis_cmd.power_limit = 0.0;
245 void burst(rm_msgs::ChassisCmd& chassis_cmd,
bool is_gyro)
247 if (cap_state_ !=
ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
249 if (is_new_capacitor_)
250 chassis_cmd.power_limit = burst_power_;
261 void applyPosturePowerScale(rm_msgs::ChassisCmd& chassis_cmd)
const
263 if (std::abs(posture_power_scale_ - 1.0) < 1e-6)
265 chassis_cmd.power_limit = std::max(0.0, std::floor(chassis_cmd.power_limit * posture_power_scale_));
268 int chassis_power_buffer_;
269 int robot_id_, chassis_power_limit_;
270 int max_power_limit_{ 70 };
272 double safety_power_{};
273 double capacitor_threshold_{};
274 double power_buffer_threshold_{ 50.0 };
275 double enable_cap_gyro_threshold_{}, disable_cap_gyro_threshold_{}, enable_use_cap_threshold_{},
276 disable_use_cap_threshold_{};
277 double charge_power_{}, extra_power_{}, burst_power_{}, standard_power_{};
278 double buffer_threshold_{};
279 double power_gain_{};
280 bool is_new_capacitor_{
false };
281 uint8_t expect_state_{}, cap_state_{};
282 bool capacitor_is_on_{
true };
283 bool allow_gyro_cap_{
false }, allow_use_cap_{
false };
284 double posture_power_scale_{ 1.0 };
286 ros::Time start_burst_time_{};
287 int total_burst_time_{};
289 bool referee_is_online_{
false };
290 bool capacity_is_online_{
false };
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:131
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:125
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:120
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:115
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
ros::Time getStartBurstTime() const
Definition power_limit.h:143
void setBurstPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:163
uint8_t getState()
Definition power_limit.h:147
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:180
void updateCapSwitchState(bool state)
Definition power_limit.h:111
void setStartBurstTime(const ros::Time start_burst_time)
Definition power_limit.h:135
void setBurstPowerLimit(const double &burst_power_limit)
Definition power_limit.h:139
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:151
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition calibration_queue.h:44