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>
73template <
class MsgType>
79 if (!nh.getParam(
"topic",
topic_))
80 ROS_ERROR(
"Topic name no defined (namespace: %s)", nh.getNamespace().c_str());
86 if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
118template <
class MsgType>
132template <
class MsgType>
151 XmlRpc::XmlRpcValue xml_rpc_value;
152 if (!nh.getParam(
"max_linear_x", xml_rpc_value))
153 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
156 if (!nh.getParam(
"max_linear_y", xml_rpc_value))
157 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
160 if (!nh.getParam(
"max_angular_z", xml_rpc_value))
161 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
165 nh.getParam(
"power_limit_topic", topic);
200 void set2DVel(
double scale_x,
double scale_y,
double scale_z)
232 XmlRpc::XmlRpcValue xml_rpc_value;
234 if (!nh.getParam(
"accel_x", xml_rpc_value))
235 ROS_ERROR(
"Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
237 accel_x_.
init(xml_rpc_value);
238 if (!nh.getParam(
"accel_y", xml_rpc_value))
239 ROS_ERROR(
"Accel Y no defined (namespace: %s)", nh.getNamespace().c_str());
241 accel_y_.
init(xml_rpc_value);
242 if (!nh.getParam(
"accel_z", xml_rpc_value))
243 ROS_ERROR(
"Accel Z no defined (namespace: %s)", nh.getNamespace().c_str());
245 accel_z_.
init(xml_rpc_value);
270 msg_.follow_vel_des = follow_vel_des;
274 msg_.wireless_state = state;
296 if (!nh.getParam(
"max_yaw_vel", max_yaw_vel_))
297 ROS_ERROR(
"Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
298 if (!nh.getParam(
"max_pitch_vel", max_pitch_vel_))
299 ROS_ERROR(
"Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
300 if (!nh.getParam(
"time_constant_rc", time_constant_rc_))
301 ROS_ERROR(
"Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
302 if (!nh.getParam(
"time_constant_pc", time_constant_pc_))
303 ROS_ERROR(
"Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
304 if (!nh.getParam(
"track_timeout", track_timeout_))
305 ROS_ERROR(
"Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
306 if (!nh.getParam(
"eject_sensitivity", eject_sensitivity_))
307 eject_sensitivity_ = 1.;
310 void setRate(
double scale_yaw,
double scale_pitch)
312 if (std::abs(scale_yaw) > 1)
313 scale_yaw = scale_yaw > 0 ? 1 : -1;
314 if (std::abs(scale_pitch) > 1)
315 scale_pitch = scale_pitch > 0 ? 1 : -1;
316 double time_constant{};
318 time_constant = time_constant_rc_;
320 time_constant = time_constant_pc_;
321 msg_.rate_yaw =
msg_.rate_yaw + (scale_yaw * max_yaw_vel_ -
msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
323 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ -
msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
326 msg_.rate_yaw *= eject_sensitivity_;
327 msg_.rate_pitch *= eject_sensitivity_;
332 msg_.traj_yaw = traj_yaw;
333 msg_.traj_pitch = traj_pitch;
337 msg_.traj_frame_id = traj_frame_id;
342 msg_.rate_pitch = 0.;
346 msg_.bullet_speed = bullet_speed;
362 msg_.target_pos = point;
366 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
367 double time_constant_rc_{}, time_constant_pc_{};
368 bool eject_flag_{}, use_rc_{};
376 ros::NodeHandle limit_nh(nh,
"heat_limit");
378 nh.param(
"speed_10m_per_speed", speed_10_, 10.);
379 nh.param(
"speed_15m_per_speed", speed_15_, 15.);
380 nh.param(
"speed_16m_per_speed", speed_16_, 16.);
381 nh.param(
"speed_18m_per_speed", speed_18_, 18.);
382 nh.param(
"speed_30m_per_speed", speed_30_, 30.);
383 nh.getParam(
"wheel_speed_10", wheel_speed_10_);
384 nh.getParam(
"wheel_speed_15", wheel_speed_15_);
385 nh.getParam(
"wheel_speed_16", wheel_speed_16_);
386 nh.getParam(
"wheel_speed_18", wheel_speed_18_);
387 nh.getParam(
"wheel_speed_30", wheel_speed_30_);
388 nh.param(
"wheel_speed_offset_front", wheel_speed_offset_front_, 0.0);
389 nh.param(
"wheel_speed_offset_back", wheel_speed_offset_back_, 0.0);
390 nh.param(
"speed_oscillation", speed_oscillation_, 1.0);
391 nh.param(
"extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
392 nh.param(
"deploy_wheel_speed", deploy_wheel_speed_, 410.0);
393 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
394 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
395 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
397 target_acceleration_tolerance_ = 0.;
398 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
400 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
401 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
402 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
403 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
404 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
406 max_track_target_vel_ = 9.0;
407 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
429 gimbal_des_error_ = error;
433 shoot_beforehand_cmd_ = data;
441 suggest_fire_ = data;
446 if (auto_wheel_speed_)
448 if (last_bullet_speed_ == 0.0)
449 last_bullet_speed_ = speed_des_;
450 if (shoot_data_.bullet_speed != last_bullet_speed_)
452 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
454 total_extra_wheel_speed_ -= 5.0;
456 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
458 total_extra_wheel_speed_ += 5.0;
461 if (shoot_data_.bullet_speed != 0.0)
462 last_bullet_speed_ = shoot_data_.bullet_speed;
467 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
469 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
471 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
473 setMode(rm_msgs::ShootCmd::READY);
477 double gimbal_error_tolerance;
478 if (track_data_.id == 12)
479 gimbal_error_tolerance = track_buff_error_tolerance_;
480 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
481 gimbal_error_tolerance = track_armor_error_tolerance_;
483 gimbal_error_tolerance = untrack_armor_error_tolerance_;
484 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
485 (track_data_.accel > target_acceleration_tolerance_)) ||
486 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
487 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
489 setMode(rm_msgs::ShootCmd::READY);
511 return deploy_wheel_speed_;
512 return wheel_speed_des_;
514 return wheel_speed_des_ + total_extra_wheel_speed_;
532 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
535 speed_des_ = speed_10_;
536 wheel_speed_des_ = wheel_speed_10_;
539 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
542 speed_des_ = speed_15_;
543 wheel_speed_des_ = wheel_speed_15_;
546 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
549 speed_des_ = speed_16_;
550 wheel_speed_des_ = wheel_speed_16_;
553 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
556 speed_des_ = speed_18_;
557 wheel_speed_des_ = wheel_speed_18_;
560 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
563 speed_des_ = speed_30_;
564 wheel_speed_des_ = wheel_speed_30_;
571 wheels_speed_offset_front_ = wheel_speed_offset_front_;
572 return wheels_speed_offset_front_;
576 wheels_speed_offset_back_ = wheel_speed_offset_back_;
577 return wheels_speed_offset_back_;
582 wheel_speed_offset_front_ -= extra_wheel_speed_once_;
584 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
589 wheel_speed_offset_front_ += extra_wheel_speed_once_;
591 total_extra_wheel_speed_ += extra_wheel_speed_once_;
595 armor_type_ = armor_type;
614 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
615 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
616 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
617 double wheel_speed_offset_front_{}, wheel_speed_offset_back_{};
618 double wheels_speed_offset_front_{}, wheels_speed_offset_back_{};
619 double track_armor_error_tolerance_{};
620 double track_buff_error_tolerance_{};
621 double untrack_armor_error_tolerance_{};
622 double max_track_target_vel_{};
623 double target_acceleration_tolerance_{};
624 double extra_wheel_speed_once_{};
625 double total_extra_wheel_speed_{};
626 double deploy_wheel_speed_{};
627 bool auto_wheel_speed_ =
false;
629 bool deploy_flag_ =
false;
630 rm_msgs::TrackData track_data_;
631 rm_msgs::GimbalDesError gimbal_des_error_;
632 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
633 rm_msgs::ShootData shoot_data_;
634 std_msgs::Bool suggest_fire_;
635 uint8_t armor_type_{};
687 msg_.leg_length = length;
695 return msg_.leg_length;
705 if (!nh.getParam(
"max_linear_x", max_linear_x_))
706 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
707 if (!nh.getParam(
"max_linear_y", max_linear_y_))
708 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
709 if (!nh.getParam(
"max_linear_z", max_linear_z_))
710 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
711 if (!nh.getParam(
"max_angular_x", max_angular_x_))
712 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
713 if (!nh.getParam(
"max_angular_y", max_angular_y_))
714 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
715 if (!nh.getParam(
"max_angular_z", max_angular_z_))
716 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
720 msg_.twist.linear.x = max_linear_x_ * scale_x;
721 msg_.twist.linear.y = max_linear_y_ * scale_y;
722 msg_.twist.linear.z = max_linear_z_ * scale_z;
726 msg_.twist.angular.x = max_angular_x_ * scale_x;
727 msg_.twist.angular.y = max_angular_y_ * scale_y;
728 msg_.twist.angular.z = max_angular_z_ * scale_z;
732 msg_.twist.linear.x = 0.;
733 msg_.twist.linear.y = 0.;
734 msg_.twist.linear.z = 0.;
735 msg_.twist.angular.x = 0.;
736 msg_.twist.angular.y = 0.;
737 msg_.twist.angular.z = 0.;
741 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
749 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
758 msg_.data = off_pos_;
763 current_position_ =
msg_.data;
764 change_position_ = current_position_ + scale * per_change_position_;
765 msg_.data = change_position_;
779 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
787 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
788 nh.getParam(
"off_pos", off_pos_));
792 msg_.data = long_pos_;
797 msg_.data = short_pos_;
802 msg_.data = off_pos_;
817 double long_pos_{}, short_pos_{}, off_pos_{};
826 ROS_ASSERT(nh.getParam(
"joint", joint_));
827 ROS_ASSERT(nh.getParam(
"step", step_));
831 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
832 if (i != joint_state_.name.end())
833 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
839 if (
msg_.data != NAN)
847 if (
msg_.data != NAN)
859 std::string joint_{};
860 const sensor_msgs::JointState& joint_state_;
870 ROS_ASSERT(nh.getParam(
"joint", joint_));
878 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
879 if (i != joint_state_.name.end())
881 index_ = std::distance(joint_state_.name.begin(), i);
886 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
893 std::string joint_{};
895 const sensor_msgs::JointState& joint_state_;
903 ROS_ASSERT(nh.getParam(
"camera_left_name", camera1_name_) && nh.getParam(
"camera_right_name", camera2_name_));
904 msg_.data = camera2_name_;
908 msg_.data = camera1_name_;
912 msg_.data = camera2_name_;
921 std::string camera1_name_{}, camera2_name_{};
939 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
942 msg_.linear.x = linear_x;
943 msg_.linear.y = linear_y;
944 msg_.linear.z = linear_z;
945 msg_.angular.x = angular_x;
946 msg_.angular.y = angular_y;
947 msg_.angular.z = angular_z;
968 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
970 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
972 ros::NodeHandle barrel_nh(nh,
"barrel");
975 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
976 barrel_nh.getParam(
"id1_point", id1_point_);
977 barrel_nh.getParam(
"id2_point", id2_point_);
978 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
979 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
980 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
981 barrel_nh.getParam(
"ready_duration", ready_duration_);
982 barrel_nh.getParam(
"switching_duration", switching_duration_);
984 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
985 &DoubleBarrelCommandSender::jointStateCallback,
this);
986 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
987 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
1041 need_switch_ =
true;
1045 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1046 last_push_time_ = time;
1051 ros::Time time = ros::Time::now();
1052 barrel_command_sender_->
setPoint(id1_point_);
1053 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1054 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1080 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1084 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1088 ros::Time time = ros::Time::now();
1089 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1090 setMode(rm_msgs::ShootCmd::READY);
1091 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1093 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1094 barrel_command_sender_->
setPoint(id2_point_);
1096 last_switch_time_ = time;
1097 need_switch_ =
false;
1098 is_switching_ =
true;
1104 ros::Time time = ros::Time::now();
1107 setMode(rm_msgs::ShootCmd::READY);
1108 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1109 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1110 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1111 is_switching_ =
false;
1117 if (!is_double_barrel_)
1122 ROS_WARN_ONCE(
"Can not get cooling limit");
1128 if (getBarrel() == shooter_ID1_cmd_sender_)
1138 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1140 trigger_error_ = data->error;
1142 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1144 joint_state_ = *data;
1146 ShooterCommandSender* shooter_ID1_cmd_sender_;
1147 ShooterCommandSender* shooter_ID2_cmd_sender_;
1148 JointPointCommandSender* barrel_command_sender_{};
1149 ros::Subscriber trigger_state_sub_;
1150 ros::Subscriber joint_state_sub_;
1151 sensor_msgs::JointState joint_state_;
1152 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1153 ros::Time last_switch_time_, last_push_time_;
1154 double ready_duration_, switching_duration_;
1155 double trigger_error_;
1156 bool is_id1_{
false };
1157 double id1_point_, id2_point_;
1158 double frequency_threshold_;
1159 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:657
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:659
int getBalanceMode()
Definition command_sender.h:667
void setZero() override
Definition command_sender.h:671
void setBalanceMode(const int mode)
Definition command_sender.h:663
Definition command_sender.h:899
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:901
void setZero() override
Definition command_sender.h:918
void switchCameraRight()
Definition command_sender.h:910
void switchCameraLeft()
Definition command_sender.h:906
void sendCommand(const ros::Time &time) override
Definition command_sender.h:914
Definition command_sender.h:783
void long_on()
Definition command_sender.h:790
void off()
Definition command_sender.h:800
void sendCommand(const ros::Time &time) override
Definition command_sender.h:809
void setZero() override
Definition command_sender.h:813
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:785
bool getState() const
Definition command_sender.h:805
void short_on()
Definition command_sender.h:795
Definition command_sender.h:228
void setFollowVelDes(double follow_vel_des)
Definition command_sender.h:268
void updateRefereeStatus(bool status)
Definition command_sender.h:264
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:252
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition command_sender.h:276
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition command_sender.h:260
ChassisCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:230
PowerLimit * power_limit_
Definition command_sender.h:285
void setZero() override
Definition command_sender.h:284
void setWirelessState(bool state)
Definition command_sender.h:272
void updateSafetyPower(int safety_power)
Definition command_sender.h:248
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:256
Definition command_sender.h:75
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:93
virtual void sendCommand(const ros::Time &time)
Definition command_sender.h:89
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:102
void setMode(int mode)
Definition command_sender.h:84
ros::Publisher pub_
Definition command_sender.h:114
uint32_t queue_size_
Definition command_sender.h:113
MsgType msg_
Definition command_sender.h:115
MsgType * getMsg()
Definition command_sender.h:106
CommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:77
std::string topic_
Definition command_sender.h:112
virtual void updateGameStatus(const rm_msgs::GameStatus data)
Definition command_sender.h:96
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition command_sender.h:99
Definition command_sender.h:964
void setZero()
Definition command_sender.h:1030
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:966
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:1010
double getSpeed()
Definition command_sender.h:1072
void setMode(int mode)
Definition command_sender.h:1026
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:1015
void sendCommand(const ros::Time &time)
Definition command_sender.h:1038
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:1005
void init()
Definition command_sender.h:1049
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:1020
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:990
void updateRefereeStatus(bool status)
Definition command_sender.h:1000
void setShootFrequency(uint8_t mode)
Definition command_sender.h:1064
void setArmorType(uint8_t armor_type)
Definition command_sender.h:1059
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:995
uint8_t getShootFrequency()
Definition command_sender.h:1068
void checkError(const ros::Time &time)
Definition command_sender.h:1034
Definition command_sender.h:292
void setGimbalTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:335
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:310
~GimbalCommandSender()=default
bool getEject() const
Definition command_sender.h:356
void setUseRc(bool flag)
Definition command_sender.h:352
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:344
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:360
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:330
void setEject(bool flag)
Definition command_sender.h:348
void setZero() override
Definition command_sender.h:339
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:294
Definition command_sender.h:134
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:136
void sendCommand(const ros::Time &time) override
Definition command_sender.h:139
Definition heat_limit.h:52
int getCoolingLimit()
Definition heat_limit.h:177
double getShootFrequency() const
Definition heat_limit.h:146
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:119
void setRefereeStatus(bool status)
Definition heat_limit.h:141
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:187
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:165
bool getShootFrequencyMode() const
Definition heat_limit.h:192
Definition command_sender.h:821
void reset()
Definition command_sender.h:829
const std::string & getJoint()
Definition command_sender.h:853
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:823
void minus()
Definition command_sender.h:845
void plus()
Definition command_sender.h:837
Definition command_sender.h:865
int getIndex()
Definition command_sender.h:876
void setZero() override
Definition command_sender.h:890
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:867
void setPoint(double point)
Definition command_sender.h:872
Definition command_sender.h:745
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:747
void sendCommand(const ros::Time &time) override
Definition command_sender.h:771
void setZero() override
Definition command_sender.h:775
bool getState() const
Definition command_sender.h:767
void changePosition(double scale)
Definition command_sender.h:761
void off()
Definition command_sender.h:756
void on()
Definition command_sender.h:751
Definition command_sender.h:675
void setZero() override
Definition command_sender.h:697
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:677
void setLgeLength(double length)
Definition command_sender.h:685
bool getJump()
Definition command_sender.h:689
double getLgeLength()
Definition command_sender.h:693
void setJump(bool jump)
Definition command_sender.h:681
Definition linear_interpolation.h:12
double output(double input)
Definition linear_interpolation.h:37
void init(XmlRpc::XmlRpcValue &config)
Definition linear_interpolation.h:15
Definition command_sender.h:925
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:939
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:927
int getMode()
Definition command_sender.h:935
void setZero() override
Definition command_sender.h:949
void setMode(int mode)
Definition command_sender.h:931
Definition power_limit.h:50
void setRefereeStatus(bool status)
Definition power_limit.h:128
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:122
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:117
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:112
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:173
void updateSafetyPower(int safety_power)
Definition power_limit.h:95
Definition command_sender.h:372
void setShootFrequency(uint8_t mode)
Definition command_sender.h:597
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:439
void setZero() override
Definition command_sender.h:605
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:419
void sendCommand(const ros::Time &time) override
Definition command_sender.h:492
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:435
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:528
uint8_t getShootFrequency()
Definition command_sender.h:601
void setDeployState(bool flag)
Definition command_sender.h:516
void setHeroState(bool flag)
Definition command_sender.h:520
void dropSpeed()
Definition command_sender.h:579
int getShootMode()
Definition command_sender.h:608
double getBackWheelSpeedOffset()
Definition command_sender.h:574
void updateRefereeStatus(bool status)
Definition command_sender.h:423
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:374
double getFrontWheelSpeedOffset()
Definition command_sender.h:569
double getWheelSpeedDes()
Definition command_sender.h:505
~ShooterCommandSender()
Definition command_sender.h:410
void raiseSpeed()
Definition command_sender.h:586
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:415
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:443
void setArmorType(uint8_t armor_type)
Definition command_sender.h:593
double getSpeed()
Definition command_sender.h:500
void checkError(const ros::Time &time)
Definition command_sender.h:465
HeatLimit * heat_limit_
Definition command_sender.h:606
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:427
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:431
bool getDeployState()
Definition command_sender.h:524
Definition command_sender.h:120
void sendCommand(const ros::Time &time) override
Definition command_sender.h:125
TimeStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:122
Definition command_sender.h:639
void setUseLio(bool flag)
Definition command_sender.h:645
void setZero() override
Definition command_sender.h:653
bool getUseLio() const
Definition command_sender.h:649
UseLioCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:641
Definition command_sender.h:147
ros::Subscriber chassis_power_limit_subscriber_
Definition command_sender.h:223
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:171
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
Definition command_sender.h:214
void setAngularZVel(double scale, double limit)
Definition command_sender.h:191
void setLinearYVel(double scale)
Definition command_sender.h:179
void setAngularZVel(double scale)
Definition command_sender.h:183
void setLinearXVel(double scale)
Definition command_sender.h:175
void set2DVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:200
double target_vel_yaw_threshold_
Definition command_sender.h:221
rm_msgs::TrackData track_data_
Definition command_sender.h:224
LinearInterp max_linear_x_
Definition command_sender.h:219
LinearInterp max_linear_y_
Definition command_sender.h:219
double vel_direction_
Definition command_sender.h:222
LinearInterp max_angular_z_
Definition command_sender.h:219
double power_limit_
Definition command_sender.h:220
void setZero() override
Definition command_sender.h:206
Vel2DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:149
Definition command_sender.h:701
void setZero() override
Definition command_sender.h:730
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:703
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:724
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:718
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44