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

#include <heat_limit.h>

Public Types

enum  ShootHz { LOW = 0, HIGH = 1, BURST = 2, MINIMAL = 3 }
 

Public Member Functions

int getCoolingHeat ()
 
int getCoolingLimit ()
 
double getShootFrequency () const
 
bool getShootFrequencyMode () const
 
int getSpeedLimit ()
 
void heatCB (const rm_msgs::LocalHeatStateConstPtr &msg)
 
 HeatLimit (ros::NodeHandle &nh)
 
void setCoolingHeatOfShooter (const rm_msgs::PowerHeatData data)
 
void setRefereeStatus (bool status)
 
void setShootFrequency (uint8_t mode)
 
void setStatusOfShooter (const rm_msgs::GameRobotStatus data)
 
void timerCB ()
 

Private Member Functions

void updateExpectShootFrequency ()
 

Private Attributes

double bullet_heat_
 
bool burst_flag_ = false
 
double burst_shoot_frequency_ {}
 
double heat_coeff_ {}
 
double high_shoot_frequency_ {}
 
ros::Publisher local_heat_pub_
 
double local_shooter_cooling_heat_ {}
 
double low_shoot_frequency_ {}
 
double minimal_shoot_frequency_ {}
 
bool referee_is_online_
 
double safe_shoot_frequency_ {}
 
double shoot_frequency_ {}
 
ros::Subscriber shoot_state_sub_
 
int shooter_cooling_heat_
 
int shooter_cooling_limit_
 
int shooter_cooling_rate_
 
uint8_t state_ {}
 
ros::Timer timer_
 
std::string type_ {}
 
bool use_local_heat_
 

Detailed Description

Definition at line 80 of file heat_limit.h.

Member Enumeration Documentation

◆ ShootHz

Enumerator
LOW 
HIGH 
BURST 
MINIMAL 

Definition at line 142 of file heat_limit.h.

Constructor & Destructor Documentation

◆ HeatLimit()

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

Definition at line 114 of file heat_limit.h.

Member Function Documentation

◆ getCoolingHeat()

int rm_common::HeatLimit::getCoolingHeat ( )
inline

Definition at line 229 of file heat_limit.h.

◆ getCoolingLimit()

int rm_common::HeatLimit::getCoolingLimit ( )
inline

Definition at line 224 of file heat_limit.h.

◆ getShootFrequency()

double rm_common::HeatLimit::getShootFrequency ( ) const
inline

Definition at line 194 of file heat_limit.h.

◆ getShootFrequencyMode()

bool rm_common::HeatLimit::getShootFrequencyMode ( ) const
inline

Definition at line 239 of file heat_limit.h.

◆ getSpeedLimit()

int rm_common::HeatLimit::getSpeedLimit ( )
inline

Definition at line 212 of file heat_limit.h.

◆ heatCB()

void rm_common::HeatLimit::heatCB ( const rm_msgs::LocalHeatStateConstPtr &  msg)
inline

Definition at line 150 of file heat_limit.h.

◆ setCoolingHeatOfShooter()

void rm_common::HeatLimit::setCoolingHeatOfShooter ( const rm_msgs::PowerHeatData  data)
inline

Definition at line 173 of file heat_limit.h.

◆ setRefereeStatus()

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

Definition at line 189 of file heat_limit.h.

◆ setShootFrequency()

void rm_common::HeatLimit::setShootFrequency ( uint8_t  mode)
inline

Definition at line 234 of file heat_limit.h.

◆ setStatusOfShooter()

void rm_common::HeatLimit::setStatusOfShooter ( const rm_msgs::GameRobotStatus  data)
inline

Definition at line 167 of file heat_limit.h.

◆ timerCB()

void rm_common::HeatLimit::timerCB ( )
inline

Definition at line 156 of file heat_limit.h.

◆ updateExpectShootFrequency()

void rm_common::HeatLimit::updateExpectShootFrequency ( )
inlineprivate

Definition at line 245 of file heat_limit.h.

Member Data Documentation

◆ bullet_heat_

double rm_common::HeatLimit::bullet_heat_
private

Definition at line 277 of file heat_limit.h.

◆ burst_flag_

bool rm_common::HeatLimit::burst_flag_ = false
private

Definition at line 276 of file heat_limit.h.

◆ burst_shoot_frequency_

double rm_common::HeatLimit::burst_shoot_frequency_ {}
private

Definition at line 278 of file heat_limit.h.

◆ heat_coeff_

double rm_common::HeatLimit::heat_coeff_ {}
private

Definition at line 277 of file heat_limit.h.

◆ high_shoot_frequency_

double rm_common::HeatLimit::high_shoot_frequency_ {}
private

Definition at line 278 of file heat_limit.h.

◆ local_heat_pub_

ros::Publisher rm_common::HeatLimit::local_heat_pub_
private

Definition at line 284 of file heat_limit.h.

◆ local_shooter_cooling_heat_

double rm_common::HeatLimit::local_shooter_cooling_heat_ {}
private

Definition at line 282 of file heat_limit.h.

◆ low_shoot_frequency_

double rm_common::HeatLimit::low_shoot_frequency_ {}
private

Definition at line 277 of file heat_limit.h.

◆ minimal_shoot_frequency_

double rm_common::HeatLimit::minimal_shoot_frequency_ {}
private

Definition at line 278 of file heat_limit.h.

◆ referee_is_online_

bool rm_common::HeatLimit::referee_is_online_
private

Definition at line 280 of file heat_limit.h.

◆ safe_shoot_frequency_

double rm_common::HeatLimit::safe_shoot_frequency_ {}
private

Definition at line 277 of file heat_limit.h.

◆ shoot_frequency_

double rm_common::HeatLimit::shoot_frequency_ {}
private

Definition at line 277 of file heat_limit.h.

◆ shoot_state_sub_

ros::Subscriber rm_common::HeatLimit::shoot_state_sub_
private

Definition at line 285 of file heat_limit.h.

◆ shooter_cooling_heat_

int rm_common::HeatLimit::shooter_cooling_heat_
private

Definition at line 281 of file heat_limit.h.

◆ shooter_cooling_limit_

int rm_common::HeatLimit::shooter_cooling_limit_
private

Definition at line 281 of file heat_limit.h.

◆ shooter_cooling_rate_

int rm_common::HeatLimit::shooter_cooling_rate_
private

Definition at line 281 of file heat_limit.h.

◆ state_

uint8_t rm_common::HeatLimit::state_ {}
private

Definition at line 274 of file heat_limit.h.

◆ timer_

ros::Timer rm_common::HeatLimit::timer_
private

Definition at line 286 of file heat_limit.h.

◆ type_

std::string rm_common::HeatLimit::type_ {}
private

Definition at line 275 of file heat_limit.h.

◆ use_local_heat_

bool rm_common::HeatLimit::use_local_heat_
private

Definition at line 280 of file heat_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