Go to the documentation of this file.
41 #include <rm_msgs/GameRobotStatus.h>
42 #include <rm_msgs/PowerHeatData.h>
43 #include <rm_msgs/ShootCmd.h>
44 #include <rm_msgs/LocalHeatState.h>
45 #include <std_msgs/Float64.h>
70 if (
type_ ==
"ID1_42MM")
88 void heatCB(
const rm_msgs::LocalHeatStateConstPtr& msg)
100 std_msgs::Float64 msg;
113 if (
type_ ==
"ID1_17MM")
117 else if (
type_ ==
"ID2_17MM")
121 else if (
type_ ==
"ID1_42MM")
136 double shooter_cooling_heat =
153 if (
type_ ==
"ID1_17MM")
154 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
155 else if (
type_ ==
"ID2_17MM")
156 return rm_msgs::ShootCmd::SPEED_30M_PER_SECOND;
157 else if (
type_ ==
"ID1_42MM")
158 return rm_msgs::ShootCmd::SPEED_16M_PER_SECOND;
int shooter_cooling_heat_
int shooter_cooling_limit_
double high_shoot_frequency_
bool getParam(const std::string &key, bool &b) const
double burst_shoot_frequency_
double local_shooter_cooling_heat_
HeatLimit(ros::NodeHandle &nh)
double getShootFrequency() const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void heatCB(const rm_msgs::LocalHeatStateConstPtr &msg)
double safe_shoot_frequency_
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
void updateExpectShootFrequency()
void setRefereeStatus(bool status)
int shooter_cooling_rate_
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
double low_shoot_frequency_
void setShootFrequency(uint8_t mode)
ros::Subscriber shoot_state_sub_
bool getShootFrequencyMode() const
ros::Publisher local_heat_pub_
T param(const std::string ¶m_name, const T &default_val) const
const std::string & getNamespace() const
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
double minimal_shoot_frequency_
rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01