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>
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());
94 safety_power_ = safety_power;
95 ROS_INFO(
"update safety power: %d", safety_power);
99 if (!capacitor_is_on_)
102 expect_state_ = state;
106 capacitor_is_on_ = state;
110 robot_id_ = data.robot_id;
111 chassis_power_limit_ = data.chassis_power_limit;
115 chassis_power_buffer_ = data.chassis_power_buffer;
116 power_buffer_threshold_ = chassis_power_buffer_ * 0.8;
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;
126 referee_is_online_ = status;
130 start_burst_time_ = start_burst_time;
134 return start_burst_time_;
138 return expect_state_;
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_;
153 if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
154 chassis_cmd.power_limit = 400;
157 if (referee_is_online_)
159 if (capacity_is_online_ && expect_state_ !=
ALLOFF)
161 if (chassis_power_limit_ > burst_power_)
162 chassis_cmd.power_limit = burst_power_;
165 switch (is_new_capacitor_ ? expect_state_ : cap_state_)
171 burst(chassis_cmd, is_gyro);
186 chassis_cmd.power_limit = safety_power_;
191 void charge(rm_msgs::ChassisCmd& chassis_cmd)
193 chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
195 void normal(rm_msgs::ChassisCmd& chassis_cmd)
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;
201 if (chassis_cmd.power_limit > max_power_limit_)
202 chassis_cmd.power_limit = max_power_limit_;
204 void zero(rm_msgs::ChassisCmd& chassis_cmd)
206 chassis_cmd.power_limit = 0.0;
208 void burst(rm_msgs::ChassisCmd& chassis_cmd,
bool is_gyro)
210 if (cap_state_ !=
ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
214 else if (ros::Time::now() - start_burst_time_ < ros::Duration(total_burst_time_))
215 chassis_cmd.power_limit = burst_power_;
217 chassis_cmd.power_limit = standard_power_;
223 int chassis_power_buffer_;
224 int robot_id_, chassis_power_limit_;
225 int max_power_limit_{ 70 };
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 };
239 ros::Time start_burst_time_{};
240 int total_burst_time_{};
242 bool referee_is_online_{
false };
243 bool capacity_is_online_{
false };
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