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>
85 ROS_INFO(
"update safety power: %d", safety_power);
107 void setCapacityData(
const rm_msgs::PowerManagementSampleAndStatusData data)
111 cap_state_ = data.state_machine_running_state;
122 void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd,
bool is_gyro)
124 if (
robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER ||
robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
125 chassis_cmd.power_limit = 400;
146 burst(chassis_cmd, is_gyro);
167 void charge(rm_msgs::ChassisCmd& chassis_cmd)
171 void normal(rm_msgs::ChassisCmd& chassis_cmd)
174 double plus_power = buffer_energy_error *
power_gain_;
178 void zero(rm_msgs::ChassisCmd& chassis_cmd)
180 chassis_cmd.power_limit = 0.0;
182 void burst(rm_msgs::ChassisCmd& chassis_cmd,
bool is_gyro)