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_burst_cap_threshold", disable_burst_cap_threshold_))
63 ROS_ERROR(
"Disable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
64 if (!nh.getParam(
"enable_burst_cap_threshold", enable_burst_cap_threshold_))
65 ROS_ERROR(
"Enable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
66 if (!nh.getParam(
"disable_normal_cap_threshold", disable_normal_cap_threshold_))
67 ROS_ERROR(
"Disable normal cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
68 if (!nh.getParam(
"enable_gyro_cap_threshold", enable_gyro_cap_threshold_))
69 ROS_ERROR(
"Enable gyro cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
70 if (!nh.getParam(
"disable_gyro_cap_threshold", disable_gyro_cap_threshold_))
71 ROS_ERROR(
"Disable gyro cap threshold 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(
"gyro_power", gyro_power_))
77 ROS_ERROR(
"Gyro power no defined (namespace: %s)", nh.getNamespace().c_str());
78 if (!nh.getParam(
"upstairs_power", upstairs_power_))
79 ROS_ERROR(
"Upstairs power no defined (namespace: %s)", nh.getNamespace().c_str());
80 if (!nh.getParam(
"max_power_limit", max_power_limit_))
81 ROS_ERROR(
"max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
82 if (!nh.getParam(
"power_gain", power_gain_))
83 ROS_ERROR(
"power gain no defined (namespace: %s)", nh.getNamespace().c_str());
84 if (!nh.getParam(
"total_burst_time", total_burst_time_))
85 ROS_ERROR(
"total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
86 default_max_power_limit_ = max_power_limit_;
87 default_burst_power_ = burst_power_;
100 if (safety_power > 0)
101 safety_power_ = safety_power;
102 ROS_INFO(
"update safety power: %d", safety_power);
106 expect_state_ = state;
110 robot_id_ = data.robot_id;
111 chassis_power_limit_ = data.chassis_power_limit;
115 chassis_power_buffer_ = data.chassis_power_buffer;
119 capacity_is_online_ = ros::Time::now() - data.stamp < ros::Duration(0.3);
120 cap_energy_ = data.capacity_remain_charge;
121 cap_state_ = data.state_machine_running_state;
125 referee_is_online_ = status;
129 start_burst_time_ = start_burst_time;
133 return start_burst_time_;
137 burst_power_ = burst_power_limit;
141 return expect_state_;
148 max_power_limit_ = upstairs_power_;
149 burst_power_ = upstairs_power_;
153 max_power_limit_ = default_max_power_limit_;
154 burst_power_ = default_burst_power_;
160 if (!allow_gyro_cap_ && cap_energy_ >= enable_gyro_cap_threshold_)
161 allow_gyro_cap_ =
true;
162 if (allow_gyro_cap_ && cap_energy_ <= disable_gyro_cap_threshold_)
163 allow_gyro_cap_ =
false;
166 chassis_cmd.power_limit = gyro_power_;
174 if (!allow_use_cap_ && cap_energy_ >= enable_burst_cap_threshold_)
175 allow_use_cap_ =
true;
176 if (allow_use_cap_ && cap_energy_ <= disable_burst_cap_threshold_)
177 allow_use_cap_ =
false;
180 chassis_cmd.power_limit = burst_power_;
188 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
189 chassis_cmd.power_limit = 400;
192 if (referee_is_online_)
194 if (capacity_is_online_ && expect_state_ !=
ALLOFF)
196 if (chassis_power_limit_ > burst_power_)
197 chassis_cmd.power_limit = burst_power_;
200 switch (expect_state_)
206 burst(chassis_cmd, is_gyro);
221 chassis_cmd.power_limit = safety_power_;
223 applyPosturePowerScale(chassis_cmd);
227 void charge(rm_msgs::ChassisCmd& chassis_cmd)
229 allow_use_cap_ =
false;
230 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
233 void normal(rm_msgs::ChassisCmd& chassis_cmd)
235 allow_use_cap_ =
false;
236 if (cap_state_ !=
ALLOFF && cap_energy_ > disable_normal_cap_threshold_ &&
237 chassis_power_buffer_ > power_buffer_threshold_)
239 chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
243 chassis_cmd.power_limit = chassis_power_limit_;
245 if (chassis_cmd.power_limit > max_power_limit_)
247 chassis_cmd.power_limit = max_power_limit_;
251 void zero(rm_msgs::ChassisCmd& chassis_cmd)
253 chassis_cmd.power_limit = 0.0;
256 void burst(rm_msgs::ChassisCmd& chassis_cmd,
bool is_gyro)
258 if (cap_state_ !=
ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
273 void applyPosturePowerScale(rm_msgs::ChassisCmd& chassis_cmd)
const
275 if (std::abs(posture_power_scale_ - 1.0) < 1e-6)
277 chassis_cmd.power_limit = std::max(0.0, std::floor(chassis_cmd.power_limit * posture_power_scale_));
280 uint8_t expect_state_{}, cap_state_{};
282 int chassis_power_buffer_{};
283 int robot_id_{}, chassis_power_limit_{};
284 double max_power_limit_{ 70.0 };
286 double safety_power_{};
287 double capacitor_threshold_{};
288 double power_buffer_threshold_{ 50.0 };
289 double enable_burst_cap_threshold_{}, disable_burst_cap_threshold_{};
290 double enable_gyro_cap_threshold_{}, disable_gyro_cap_threshold_{};
291 double disable_normal_cap_threshold_{};
292 double extra_power_{}, burst_power_{}, gyro_power_{}, upstairs_power_{};
293 double default_max_power_limit_{}, default_burst_power_{};
294 double power_gain_{};
296 bool allow_gyro_cap_{
false }, allow_use_cap_{
false };
297 double posture_power_scale_{ 1.0 };
299 ros::Time start_burst_time_{};
300 int total_burst_time_{};
302 bool referee_is_online_{
false };
303 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:123
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:117
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: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
void setUpstairsPower(bool upstairs)
Definition power_limit.h:144
ros::Time getStartBurstTime() const
Definition power_limit.h:131
void setBurstPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:172
uint8_t getState()
Definition power_limit.h:139
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:186
void setStartBurstTime(const ros::Time start_burst_time)
Definition power_limit.h:127
void setBurstPowerLimit(const double &burst_power_limit)
Definition power_limit.h:135
void setGyroPower(rm_msgs::ChassisCmd &chassis_cmd)
Definition power_limit.h:158
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition calibration_queue.h:44