Go to the documentation of this file.
40 #include <type_traits>
44 #include <rm_msgs/ChassisCmd.h>
45 #include <rm_msgs/GimbalCmd.h>
46 #include <rm_msgs/ShootCmd.h>
47 #include <rm_msgs/ShootBeforehandCmd.h>
48 #include <rm_msgs/GimbalDesError.h>
49 #include <rm_msgs/StateCmd.h>
50 #include <rm_msgs/TrackData.h>
51 #include <rm_msgs/GameRobotHp.h>
52 #include <rm_msgs/StatusChangeRequest.h>
53 #include <rm_msgs/ShootData.h>
54 #include <rm_msgs/LegCmd.h>
55 #include <geometry_msgs/TwistStamped.h>
56 #include <sensor_msgs/JointState.h>
57 #include <nav_msgs/Odometry.h>
58 #include <std_msgs/UInt8.h>
59 #include <std_msgs/Float64.h>
60 #include <rm_msgs/MultiDofCmd.h>
61 #include <std_msgs/String.h>
62 #include <std_msgs/Bool.h>
63 #include <control_msgs/JointControllerState.h>
73 template <
class MsgType>
74 class CommandSenderBase
86 if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
99 virtual void updateCapacityData(
const rm_msgs::PowerManagementSampleAndStatusData data)
118 template <
class MsgType>
119 class TimeStampCommandSenderBase :
public CommandSenderBase<MsgType>
132 template <
class MsgType>
133 class HeaderStampCommandSenderBase :
public CommandSenderBase<MsgType>
152 if (!nh.
getParam(
"max_linear_x", xml_rpc_value))
160 if (!nh.
getParam(
"max_angular_z", xml_rpc_value))
165 nh.
getParam(
"power_limit_topic", topic);
200 void set2DVel(
double scale_x,
double scale_y,
double scale_z)
234 if (!nh.
getParam(
"accel_x", xml_rpc_value))
238 if (!nh.
getParam(
"accel_y", xml_rpc_value))
242 if (!nh.
getParam(
"accel_z", xml_rpc_value))
260 void updateCapacityData(
const rm_msgs::PowerManagementSampleAndStatusData data)
override
270 msg_.follow_vel_des = follow_vel_des;
306 void setRate(
double scale_yaw,
double scale_pitch)
308 if (std::abs(scale_yaw) > 1)
309 scale_yaw = scale_yaw > 0 ? 1 : -1;
310 if (std::abs(scale_pitch) > 1)
311 scale_pitch = scale_pitch > 0 ? 1 : -1;
312 double time_constant{};
328 msg_.traj_yaw = traj_yaw;
329 msg_.traj_pitch = traj_pitch;
334 msg_.rate_pitch = 0.;
338 msg_.bullet_speed = bullet_speed;
352 void setPoint(geometry_msgs::PointStamped point)
354 msg_.target_pos = point;
387 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.
getNamespace().c_str());
462 setMode(rm_msgs::ShootCmd::READY);
466 double gimbal_error_tolerance;
476 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
477 setMode(rm_msgs::ShootCmd::READY);
499 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
506 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
513 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
520 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
527 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
618 return msg_.leg_length;
641 void setLinearVel(
double scale_x,
double scale_y,
double scale_z)
655 msg_.twist.linear.x = 0.;
656 msg_.twist.linear.y = 0.;
658 msg_.twist.angular.x = 0.;
659 msg_.twist.angular.y = 0.;
660 msg_.twist.angular.z = 0.;
667 class JointPositionBinaryCommandSender :
public CommandSenderBase<std_msgs::Float64>
743 class JointJogCommandSender :
public CommandSenderBase<std_msgs::Float64>
762 if (
msg_.data != NAN)
787 class JointPointCommandSender :
public CommandSenderBase<std_msgs::Float64>
843 class MultiDofCommandSender :
public TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>
858 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
861 msg_.linear.x = linear_x;
862 msg_.linear.y = linear_y;
863 msg_.linear.z = linear_z;
865 msg_.angular.y = angular_y;
866 msg_.angular.z = angular_z;
964 if (
getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1026 setMode(rm_msgs::ShootCmd::READY);
CommandSenderBase(ros::NodeHandle &nh)
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
ShooterCommandSender * getBarrel()
uint8_t getShootFrequency()
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
LinearInterp max_linear_x_
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
const std::string & getJoint()
LinearInterp max_linear_y_
rm_msgs::TrackData track_data_
void setShootFrequency(uint8_t mode)
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
ros::Subscriber chassis_power_limit_subscriber_
bool getParam(const std::string &key, bool &b) const
double check_switch_threshold_
Vel3DCommandSender(ros::NodeHandle &nh)
double output(double input)
void updateSafetyPower(int safety_power)
double track_armor_error_tolerance_
CameraSwitchCommandSender(ros::NodeHandle &nh)
void updateRefereeStatus(bool status)
void jointStateCallback(const sensor_msgs::JointState::ConstPtr &data)
BalanceCommandSender(ros::NodeHandle &nh)
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
void changePosition(double scale)
void updateSuggestFireData(const std_msgs::Bool &data)
double per_change_position_
void setAngularVel(double scale_x, double scale_y, double scale_z)
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
#define ROS_WARN_ONCE(...)
CardCommandSender(ros::NodeHandle &nh)
double target_vel_yaw_threshold_
~MultiDofCommandSender()=default
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
ros::Subscriber trigger_state_sub_
double getShootFrequency() const
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
void setAngularZVel(double scale)
void updateRefereeStatus(bool status)
void publish(const boost::shared_ptr< M > &message) const
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Publisher advertise(AdvertiseOptions &ops)
ros::Time last_push_time_
void setRate(double scale_yaw, double scale_pitch)
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
double speed_oscillation_
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
void setRefereeStatus(bool status)
void sendCommand(const ros::Time &time) override
TimeStampCommandSenderBase(ros::NodeHandle &nh)
void setRefereeStatus(bool status)
double frequency_threshold_
void setLinearVel(double scale_x, double scale_y, double scale_z)
std::string camera1_name_
double track_buff_error_tolerance_
void setPoint(geometry_msgs::PointStamped point)
double getWheelSpeedDes()
PowerLimit * power_limit_
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
void sendCommand(const ros::Time &time)
ros::Time last_switch_time_
void setLgeLength(double length)
GimbalCommandSender(ros::NodeHandle &nh)
virtual void updateGameStatus(const rm_msgs::GameStatus data)
rm_msgs::ShootData shoot_data_
LegCommandSender(ros::NodeHandle &nh)
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
std_msgs::Bool suggest_fire_
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
double last_bullet_speed_
void sendCommand(const ros::Time &time) override
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())
void setLinearXVel(double scale)
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
void updateRefereeStatus(bool status)
virtual void sendCommand(const ros::Time &time)
void updateTrackData(const rm_msgs::TrackData &data)
const sensor_msgs::JointState & joint_state_
void checkError(const ros::Time &time)
double eject_sensitivity_
LinearInterp max_angular_z_
void updateTrackData(const rm_msgs::TrackData &data)
void setArmorType(uint8_t armor_type)
void setShootFrequency(uint8_t mode)
sensor_msgs::JointState joint_state_
void checkError(const ros::Time &time)
rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_
ShooterCommandSender * shooter_ID2_cmd_sender_
double total_extra_wheel_speed_
void sendCommand(const ros::Time &time) override
bool getShootFrequencyMode() const
double check_launch_threshold_
void updateShootData(const rm_msgs::ShootData &data)
MultiDofCommandSender(ros::NodeHandle &nh)
double max_track_target_vel_
void setPoint(double point)
void setArmorType(uint8_t armor_type)
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
double extra_wheel_speed_once_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ShooterCommandSender(ros::NodeHandle &nh)
void sendChassisCommand(const ros::Time &time, bool is_gyro)
void setShootFrequency(uint8_t mode)
void setGameRobotData(const rm_msgs::GameRobotStatus data)
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
void triggerStateCallback(const control_msgs::JointControllerState::ConstPtr &data)
T param(const std::string ¶m_name, const T &default_val) const
rm_msgs::GimbalDesError gimbal_des_error_
ros::Subscriber joint_state_sub_
std::string camera2_name_
void updateSafetyPower(int safety_power)
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
void setLinearYVel(double scale)
rm_msgs::TrackData track_data_
void setBulletSpeed(double bullet_speed)
DoubleBarrelCommandSender(ros::NodeHandle &nh)
~GimbalCommandSender()=default
double switching_duration_
void updateTrackData(const rm_msgs::TrackData &data)
Vel2DCommandSender(ros::NodeHandle &nh)
uint8_t getShootFrequency()
void setSpeedDesAndWheelSpeedDes()
void sendCommand(const ros::Time &time) override
const std::string & getNamespace() const
ShooterCommandSender * shooter_ID1_cmd_sender_
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
const sensor_msgs::JointState & joint_state_
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
void setFollowVelDes(double follow_vel_des)
void updateSuggestFireData(const std_msgs::Bool &data)
void init(XmlRpc::XmlRpcValue &config)
void sendCommand(const ros::Time &time) override
void setBalanceMode(const int mode)
JointPointCommandSender * barrel_command_sender_
void setGimbalTraj(double traj_yaw, double traj_pitch)
double untrack_armor_error_tolerance_
void set2DVel(double scale_x, double scale_y, double scale_z)
void sendCommand(const ros::Time &time) override
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
ChassisCommandSender(ros::NodeHandle &nh)
double target_acceleration_tolerance_
rm_common
Author(s):
autogenerated on Wed Apr 9 2025 02:22:16