Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
rm_common::PowerLimit Class Reference

#include <power_limit.h>

Public Types

enum  Mode {
  CHARGE = 0, BURST = 1, NORMAL = 2, ALLOFF = 3,
  TEST = 4
}
 

Public Member Functions

uint8_t getState ()
 
 PowerLimit (ros::NodeHandle &nh)
 
void setCapacityData (const rm_msgs::PowerManagementSampleAndStatusData data)
 
void setChassisPowerBuffer (const rm_msgs::PowerHeatData data)
 
void setGameRobotData (const rm_msgs::GameRobotStatus data)
 
void setLimitPower (rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
 
void setRefereeStatus (bool status)
 
void updateCapSwitchState (bool state)
 
void updateSafetyPower (int safety_power)
 
void updateState (uint8_t state)
 

Private Member Functions

void burst (rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
 
void charge (rm_msgs::ChassisCmd &chassis_cmd)
 
void normal (rm_msgs::ChassisCmd &chassis_cmd)
 
void zero (rm_msgs::ChassisCmd &chassis_cmd)
 

Private Attributes

double buffer_threshold_ {}
 
double burst_power_ {}
 
float cap_energy_
 
uint8_t cap_state_ {}
 
bool capacitor_is_on_ { true }
 
double capacitor_threshold_ {}
 
bool capacity_is_online_ { false }
 
double charge_power_ {}
 
int chassis_power_buffer_
 
int chassis_power_limit_
 
uint8_t expect_state_ {}
 
double extra_power_ {}
 
bool is_new_capacitor_ { false }
 
double power_gain_ {}
 
bool referee_is_online_ { false }
 
int robot_id_
 
double safety_power_ {}
 

Detailed Description

Definition at line 80 of file power_limit.h.

Member Enumeration Documentation

◆ Mode

Enumerator
CHARGE 
BURST 
NORMAL 
ALLOFF 
TEST 

Definition at line 134 of file power_limit.h.

Constructor & Destructor Documentation

◆ PowerLimit()

rm_common::PowerLimit::PowerLimit ( ros::NodeHandle nh)
inline

Definition at line 114 of file power_limit.h.

Member Function Documentation

◆ burst()

void rm_common::PowerLimit::burst ( rm_msgs::ChassisCmd &  chassis_cmd,
bool  is_gyro 
)
inlineprivate

Definition at line 244 of file power_limit.h.

◆ charge()

void rm_common::PowerLimit::charge ( rm_msgs::ChassisCmd &  chassis_cmd)
inlineprivate

Definition at line 229 of file power_limit.h.

◆ getState()

uint8_t rm_common::PowerLimit::getState ( )
inline

Definition at line 180 of file power_limit.h.

◆ normal()

void rm_common::PowerLimit::normal ( rm_msgs::ChassisCmd &  chassis_cmd)
inlineprivate

Definition at line 233 of file power_limit.h.

◆ setCapacityData()

void rm_common::PowerLimit::setCapacityData ( const rm_msgs::PowerManagementSampleAndStatusData  data)
inline

Definition at line 169 of file power_limit.h.

◆ setChassisPowerBuffer()

void rm_common::PowerLimit::setChassisPowerBuffer ( const rm_msgs::PowerHeatData  data)
inline

Definition at line 165 of file power_limit.h.

◆ setGameRobotData()

void rm_common::PowerLimit::setGameRobotData ( const rm_msgs::GameRobotStatus  data)
inline

Definition at line 160 of file power_limit.h.

◆ setLimitPower()

void rm_common::PowerLimit::setLimitPower ( rm_msgs::ChassisCmd &  chassis_cmd,
bool  is_gyro 
)
inline

Definition at line 184 of file power_limit.h.

◆ setRefereeStatus()

void rm_common::PowerLimit::setRefereeStatus ( bool  status)
inline

Definition at line 175 of file power_limit.h.

◆ updateCapSwitchState()

void rm_common::PowerLimit::updateCapSwitchState ( bool  state)
inline

Definition at line 156 of file power_limit.h.

◆ updateSafetyPower()

void rm_common::PowerLimit::updateSafetyPower ( int  safety_power)
inline

Definition at line 143 of file power_limit.h.

◆ updateState()

void rm_common::PowerLimit::updateState ( uint8_t  state)
inline

Definition at line 149 of file power_limit.h.

◆ zero()

void rm_common::PowerLimit::zero ( rm_msgs::ChassisCmd &  chassis_cmd)
inlineprivate

Definition at line 240 of file power_limit.h.

Member Data Documentation

◆ buffer_threshold_

double rm_common::PowerLimit::buffer_threshold_ {}
private

Definition at line 263 of file power_limit.h.

◆ burst_power_

double rm_common::PowerLimit::burst_power_ {}
private

Definition at line 262 of file power_limit.h.

◆ cap_energy_

float rm_common::PowerLimit::cap_energy_
private

Definition at line 259 of file power_limit.h.

◆ cap_state_

uint8_t rm_common::PowerLimit::cap_state_ {}
private

Definition at line 266 of file power_limit.h.

◆ capacitor_is_on_

bool rm_common::PowerLimit::capacitor_is_on_ { true }
private

Definition at line 267 of file power_limit.h.

◆ capacitor_threshold_

double rm_common::PowerLimit::capacitor_threshold_ {}
private

Definition at line 261 of file power_limit.h.

◆ capacity_is_online_

bool rm_common::PowerLimit::capacity_is_online_ { false }
private

Definition at line 270 of file power_limit.h.

◆ charge_power_

double rm_common::PowerLimit::charge_power_ {}
private

Definition at line 262 of file power_limit.h.

◆ chassis_power_buffer_

int rm_common::PowerLimit::chassis_power_buffer_
private

Definition at line 257 of file power_limit.h.

◆ chassis_power_limit_

int rm_common::PowerLimit::chassis_power_limit_
private

Definition at line 258 of file power_limit.h.

◆ expect_state_

uint8_t rm_common::PowerLimit::expect_state_ {}
private

Definition at line 266 of file power_limit.h.

◆ extra_power_

double rm_common::PowerLimit::extra_power_ {}
private

Definition at line 262 of file power_limit.h.

◆ is_new_capacitor_

bool rm_common::PowerLimit::is_new_capacitor_ { false }
private

Definition at line 265 of file power_limit.h.

◆ power_gain_

double rm_common::PowerLimit::power_gain_ {}
private

Definition at line 264 of file power_limit.h.

◆ referee_is_online_

bool rm_common::PowerLimit::referee_is_online_ { false }
private

Definition at line 269 of file power_limit.h.

◆ robot_id_

int rm_common::PowerLimit::robot_id_
private

Definition at line 258 of file power_limit.h.

◆ safety_power_

double rm_common::PowerLimit::safety_power_ {}
private

Definition at line 260 of file power_limit.h.


The documentation for this class was generated from the following file:


rm_common
Author(s):
autogenerated on Thu Apr 3 2025 02:22:31