44#include <rm_msgs/ChassisCmd.h>
45#include <rm_msgs/ChassisActiveSusCmd.h>
46#include <rm_msgs/GimbalCmd.h>
47#include <rm_msgs/ShootCmd.h>
48#include <rm_msgs/ShootBeforehandCmd.h>
49#include <rm_msgs/GimbalDesError.h>
50#include <rm_msgs/StateCmd.h>
51#include <rm_msgs/TrackData.h>
52#include <rm_msgs/GameRobotHp.h>
53#include <rm_msgs/StatusChangeRequest.h>
54#include <rm_msgs/ShootData.h>
55#include <rm_msgs/LegCmd.h>
56#include <geometry_msgs/TwistStamped.h>
57#include <sensor_msgs/JointState.h>
58#include <nav_msgs/Odometry.h>
59#include <std_msgs/UInt8.h>
60#include <std_msgs/Float64.h>
61#include <rm_msgs/MultiDofCmd.h>
62#include <std_msgs/String.h>
63#include <std_msgs/Bool.h>
64#include <control_msgs/JointControllerState.h>
65#include <std_msgs/Float32.h>
75template <
class MsgType>
81 if (!nh.getParam(
"topic",
topic_))
82 ROS_ERROR(
"Topic name no defined (namespace: %s)", nh.getNamespace().c_str());
88 if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
120template <
class MsgType>
134template <
class MsgType>
153 XmlRpc::XmlRpcValue xml_rpc_value;
154 if (!nh.getParam(
"max_linear_x", xml_rpc_value))
155 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
158 if (!nh.getParam(
"max_linear_y", xml_rpc_value))
159 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
162 if (!nh.getParam(
"max_angular_z", xml_rpc_value))
163 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
167 nh.getParam(
"power_limit_topic", topic);
202 void set2DVel(
double scale_x,
double scale_y,
double scale_z)
234 XmlRpc::XmlRpcValue xml_rpc_value;
236 if (!nh.getParam(
"accel_x", xml_rpc_value))
237 ROS_ERROR(
"Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
239 accel_x_.
init(xml_rpc_value);
240 if (!nh.getParam(
"accel_y", xml_rpc_value))
241 ROS_ERROR(
"Accel Y no defined (namespace: %s)", nh.getNamespace().c_str());
243 accel_y_.
init(xml_rpc_value);
244 if (!nh.getParam(
"accel_z", xml_rpc_value))
245 ROS_ERROR(
"Accel Z no defined (namespace: %s)", nh.getNamespace().c_str());
247 accel_z_.
init(xml_rpc_value);
272 msg_.follow_vel_des = follow_vel_des;
276 msg_.wireless_state = state;
310 if (!nh.getParam(
"max_yaw_vel", max_yaw_vel_))
311 ROS_ERROR(
"Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
312 if (!nh.getParam(
"max_pitch_vel", max_pitch_vel_))
313 ROS_ERROR(
"Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
314 if (!nh.getParam(
"time_constant_rc", time_constant_rc_))
315 ROS_ERROR(
"Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
316 if (!nh.getParam(
"time_constant_pc", time_constant_pc_))
317 ROS_ERROR(
"Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
318 if (!nh.getParam(
"track_timeout", track_timeout_))
319 ROS_ERROR(
"Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
320 if (!nh.getParam(
"eject_sensitivity", eject_sensitivity_))
321 eject_sensitivity_ = 1.;
324 void setRate(
double scale_yaw,
double scale_pitch)
326 if (std::abs(scale_yaw) > 1)
327 scale_yaw = scale_yaw > 0 ? 1 : -1;
328 if (std::abs(scale_pitch) > 1)
329 scale_pitch = scale_pitch > 0 ? 1 : -1;
330 double time_constant{};
332 time_constant = time_constant_rc_;
334 time_constant = time_constant_pc_;
335 msg_.rate_yaw =
msg_.rate_yaw + (scale_yaw * max_yaw_vel_ -
msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
337 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ -
msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
340 msg_.rate_yaw *= eject_sensitivity_;
341 msg_.rate_pitch *= eject_sensitivity_;
346 msg_.traj_yaw = traj_yaw;
347 msg_.traj_pitch = traj_pitch;
351 msg_.traj_frame_id = traj_frame_id;
356 msg_.rate_pitch = 0.;
360 msg_.bullet_speed = bullet_speed;
376 msg_.target_pos = point;
380 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
381 double time_constant_rc_{}, time_constant_pc_{};
382 bool eject_flag_{}, use_rc_{};
390 ros::NodeHandle limit_nh(nh,
"heat_limit");
392 nh.param(
"speed_10m_per_speed", speed_10_, 10.);
393 nh.param(
"speed_15m_per_speed", speed_15_, 15.);
394 nh.param(
"speed_16m_per_speed", speed_16_, 16.);
395 nh.param(
"speed_18m_per_speed", speed_18_, 18.);
396 nh.param(
"speed_30m_per_speed", speed_30_, 30.);
397 nh.getParam(
"wheel_speed_10", wheel_speed_10_);
398 nh.getParam(
"wheel_speed_15", wheel_speed_15_);
399 nh.getParam(
"wheel_speed_16", wheel_speed_16_);
400 nh.getParam(
"wheel_speed_18", wheel_speed_18_);
401 nh.getParam(
"wheel_speed_30", wheel_speed_30_);
402 nh.param(
"wheel_speed_offset_front", wheel_speed_offset_front_, 0.0);
403 nh.param(
"wheel_speed_offset_back", wheel_speed_offset_back_, 0.0);
404 nh.param(
"speed_oscillation", speed_oscillation_, 1.0);
405 nh.param(
"extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
406 nh.param(
"deploy_wheel_speed", deploy_wheel_speed_, 410.0);
407 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
408 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
409 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
411 target_acceleration_tolerance_ = 0.;
412 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
414 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
415 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
416 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
417 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
418 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
420 max_track_target_vel_ = 9.0;
421 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
443 gimbal_des_error_ = error;
447 shoot_beforehand_cmd_ = data;
455 suggest_fire_ = data;
460 if (auto_wheel_speed_)
462 if (last_bullet_speed_ == 0.0)
463 last_bullet_speed_ = speed_des_;
464 if (shoot_data_.bullet_speed != last_bullet_speed_)
466 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
468 total_extra_wheel_speed_ -= 5.0;
470 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
472 total_extra_wheel_speed_ += 5.0;
475 if (shoot_data_.bullet_speed != 0.0)
476 last_bullet_speed_ = shoot_data_.bullet_speed;
481 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
483 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
485 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
487 setMode(rm_msgs::ShootCmd::READY);
491 double gimbal_error_tolerance;
492 if (track_data_.id == 12)
493 gimbal_error_tolerance = track_buff_error_tolerance_;
494 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
495 gimbal_error_tolerance = track_armor_error_tolerance_;
497 gimbal_error_tolerance = untrack_armor_error_tolerance_;
498 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
499 (track_data_.accel > target_acceleration_tolerance_)) ||
500 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
501 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
503 setMode(rm_msgs::ShootCmd::READY);
525 return deploy_wheel_speed_;
526 return wheel_speed_des_;
528 return wheel_speed_des_ + total_extra_wheel_speed_;
546 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
549 speed_des_ = speed_10_;
550 wheel_speed_des_ = wheel_speed_10_;
553 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
556 speed_des_ = speed_15_;
557 wheel_speed_des_ = wheel_speed_15_;
560 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
563 speed_des_ = speed_16_;
564 wheel_speed_des_ = wheel_speed_16_;
567 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
570 speed_des_ = speed_18_;
571 wheel_speed_des_ = wheel_speed_18_;
574 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
577 speed_des_ = speed_30_;
578 wheel_speed_des_ = wheel_speed_30_;
585 wheels_speed_offset_front_ = wheel_speed_offset_front_;
586 return wheels_speed_offset_front_;
590 wheels_speed_offset_back_ = wheel_speed_offset_back_;
591 return wheels_speed_offset_back_;
596 wheel_speed_offset_front_ -= extra_wheel_speed_once_;
598 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
603 wheel_speed_offset_front_ += extra_wheel_speed_once_;
605 total_extra_wheel_speed_ += extra_wheel_speed_once_;
609 armor_type_ = armor_type;
628 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
629 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
630 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
631 double wheel_speed_offset_front_{}, wheel_speed_offset_back_{};
632 double wheels_speed_offset_front_{}, wheels_speed_offset_back_{};
633 double track_armor_error_tolerance_{};
634 double track_buff_error_tolerance_{};
635 double untrack_armor_error_tolerance_{};
636 double max_track_target_vel_{};
637 double target_acceleration_tolerance_{};
638 double extra_wheel_speed_once_{};
639 double total_extra_wheel_speed_{};
640 double deploy_wheel_speed_{};
641 bool auto_wheel_speed_ =
false;
643 bool deploy_flag_ =
false;
644 rm_msgs::TrackData track_data_;
645 rm_msgs::GimbalDesError gimbal_des_error_;
646 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
647 rm_msgs::ShootData shoot_data_;
648 std_msgs::Bool suggest_fire_;
649 uint8_t armor_type_{};
701 msg_.leg_length = length;
709 return msg_.leg_length;
719 if (!nh.getParam(
"max_linear_x", max_linear_x_))
720 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
721 if (!nh.getParam(
"max_linear_y", max_linear_y_))
722 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
723 if (!nh.getParam(
"max_linear_z", max_linear_z_))
724 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
725 if (!nh.getParam(
"max_angular_x", max_angular_x_))
726 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
727 if (!nh.getParam(
"max_angular_y", max_angular_y_))
728 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
729 if (!nh.getParam(
"max_angular_z", max_angular_z_))
730 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
734 msg_.twist.linear.x = max_linear_x_ * scale_x;
735 msg_.twist.linear.y = max_linear_y_ * scale_y;
736 msg_.twist.linear.z = max_linear_z_ * scale_z;
740 msg_.twist.angular.x = max_angular_x_ * scale_x;
741 msg_.twist.angular.y = max_angular_y_ * scale_y;
742 msg_.twist.angular.z = max_angular_z_ * scale_z;
746 msg_.twist.linear.x = 0.;
747 msg_.twist.linear.y = 0.;
748 msg_.twist.linear.z = 0.;
749 msg_.twist.angular.x = 0.;
750 msg_.twist.angular.y = 0.;
751 msg_.twist.angular.z = 0.;
755 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
763 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
772 msg_.data = off_pos_;
777 current_position_ =
msg_.data;
778 change_position_ = current_position_ + scale * per_change_position_;
779 msg_.data = change_position_;
793 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
801 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
802 nh.getParam(
"off_pos", off_pos_));
806 msg_.data = long_pos_;
811 msg_.data = short_pos_;
816 msg_.data = off_pos_;
831 double long_pos_{}, short_pos_{}, off_pos_{};
840 ROS_ASSERT(nh.getParam(
"joint", joint_));
841 ROS_ASSERT(nh.getParam(
"step", step_));
845 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
846 if (i != joint_state_.name.end())
847 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
853 if (
msg_.data != NAN)
861 if (
msg_.data != NAN)
873 std::string joint_{};
874 const sensor_msgs::JointState& joint_state_;
884 ROS_ASSERT(nh.getParam(
"joint", joint_));
892 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
893 if (i != joint_state_.name.end())
895 index_ = std::distance(joint_state_.name.begin(), i);
900 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
907 std::string joint_{};
909 const sensor_msgs::JointState& joint_state_;
917 ROS_ASSERT(nh.getParam(
"camera_left_name", camera1_name_) && nh.getParam(
"camera_right_name", camera2_name_));
918 msg_.data = camera2_name_;
922 msg_.data = camera1_name_;
926 msg_.data = camera2_name_;
935 std::string camera1_name_{}, camera2_name_{};
953 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
956 msg_.linear.x = linear_x;
957 msg_.linear.y = linear_y;
958 msg_.linear.z = linear_z;
959 msg_.angular.x = angular_x;
960 msg_.angular.y = angular_y;
961 msg_.angular.z = angular_z;
982 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
984 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
986 ros::NodeHandle barrel_nh(nh,
"barrel");
989 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
990 barrel_nh.getParam(
"id1_point", id1_point_);
991 barrel_nh.getParam(
"id2_point", id2_point_);
992 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
993 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
994 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
995 barrel_nh.getParam(
"ready_duration", ready_duration_);
996 barrel_nh.getParam(
"switching_duration", switching_duration_);
998 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
999 &DoubleBarrelCommandSender::jointStateCallback,
this);
1000 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
1001 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
1055 need_switch_ =
true;
1059 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1060 last_push_time_ = time;
1065 ros::Time time = ros::Time::now();
1066 barrel_command_sender_->
setPoint(id1_point_);
1067 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1068 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1094 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1098 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1102 ros::Time time = ros::Time::now();
1103 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1104 setMode(rm_msgs::ShootCmd::READY);
1105 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1107 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1108 barrel_command_sender_->
setPoint(id2_point_);
1110 last_switch_time_ = time;
1111 need_switch_ =
false;
1112 is_switching_ =
true;
1118 ros::Time time = ros::Time::now();
1121 setMode(rm_msgs::ShootCmd::READY);
1122 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1123 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1124 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1125 is_switching_ =
false;
1131 if (!is_double_barrel_)
1136 ROS_WARN_ONCE(
"Can not get cooling limit");
1142 if (getBarrel() == shooter_ID1_cmd_sender_)
1152 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1154 trigger_error_ = data->error;
1156 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1158 joint_state_ = *data;
1160 ShooterCommandSender* shooter_ID1_cmd_sender_;
1161 ShooterCommandSender* shooter_ID2_cmd_sender_;
1162 JointPointCommandSender* barrel_command_sender_{};
1163 ros::Subscriber trigger_state_sub_;
1164 ros::Subscriber joint_state_sub_;
1165 sensor_msgs::JointState joint_state_;
1166 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1167 ros::Time last_switch_time_, last_push_time_;
1168 double ready_duration_, switching_duration_;
1169 double trigger_error_;
1170 bool is_id1_{
false };
1171 double id1_point_, id2_point_;
1172 double frequency_threshold_;
1173 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:671
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:673
int getBalanceMode()
Definition command_sender.h:681
void setZero() override
Definition command_sender.h:685
void setBalanceMode(const int mode)
Definition command_sender.h:677
Definition command_sender.h:913
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:915
void setZero() override
Definition command_sender.h:932
void switchCameraRight()
Definition command_sender.h:924
void switchCameraLeft()
Definition command_sender.h:920
void sendCommand(const ros::Time &time) override
Definition command_sender.h:928
Definition command_sender.h:797
void long_on()
Definition command_sender.h:804
void off()
Definition command_sender.h:814
void sendCommand(const ros::Time &time) override
Definition command_sender.h:823
void setZero() override
Definition command_sender.h:827
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:799
bool getState() const
Definition command_sender.h:819
void short_on()
Definition command_sender.h:809
Definition command_sender.h:294
void setZero() override
Definition command_sender.h:300
ChassisActiveSuspensionCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:296
Definition command_sender.h:230
void setFollowVelDes(double follow_vel_des)
Definition command_sender.h:270
void updateRefereeStatus(bool status)
Definition command_sender.h:266
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:254
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition command_sender.h:278
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition command_sender.h:262
ChassisCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:232
PowerLimit * power_limit_
Definition command_sender.h:287
void setZero() override
Definition command_sender.h:286
void setWirelessState(bool state)
Definition command_sender.h:274
void updateSafetyPower(int safety_power)
Definition command_sender.h:250
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:258
Definition command_sender.h:77
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:95
virtual void sendCommand(const ros::Time &time)
Definition command_sender.h:91
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:104
void setMode(int mode)
Definition command_sender.h:86
ros::Publisher pub_
Definition command_sender.h:116
uint32_t queue_size_
Definition command_sender.h:115
MsgType msg_
Definition command_sender.h:117
MsgType * getMsg()
Definition command_sender.h:108
CommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:79
std::string topic_
Definition command_sender.h:114
virtual void updateGameStatus(const rm_msgs::GameStatus data)
Definition command_sender.h:98
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition command_sender.h:101
Definition command_sender.h:978
void setZero()
Definition command_sender.h:1044
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:980
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:1024
double getSpeed()
Definition command_sender.h:1086
void setMode(int mode)
Definition command_sender.h:1040
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:1029
void sendCommand(const ros::Time &time)
Definition command_sender.h:1052
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:1019
void init()
Definition command_sender.h:1063
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:1034
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:1004
void updateRefereeStatus(bool status)
Definition command_sender.h:1014
void setShootFrequency(uint8_t mode)
Definition command_sender.h:1078
void setArmorType(uint8_t armor_type)
Definition command_sender.h:1073
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:1009
uint8_t getShootFrequency()
Definition command_sender.h:1082
void checkError(const ros::Time &time)
Definition command_sender.h:1048
Definition command_sender.h:306
void setGimbalTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:349
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:324
~GimbalCommandSender()=default
bool getEject() const
Definition command_sender.h:370
void setUseRc(bool flag)
Definition command_sender.h:366
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:358
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:374
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:344
void setEject(bool flag)
Definition command_sender.h:362
void setZero() override
Definition command_sender.h:353
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:308
Definition command_sender.h:136
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:138
void sendCommand(const ros::Time &time) override
Definition command_sender.h:141
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:835
void reset()
Definition command_sender.h:843
const std::string & getJoint()
Definition command_sender.h:867
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:837
void minus()
Definition command_sender.h:859
void plus()
Definition command_sender.h:851
Definition command_sender.h:879
int getIndex()
Definition command_sender.h:890
void setZero() override
Definition command_sender.h:904
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:881
void setPoint(double point)
Definition command_sender.h:886
Definition command_sender.h:759
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:761
void sendCommand(const ros::Time &time) override
Definition command_sender.h:785
void setZero() override
Definition command_sender.h:789
bool getState() const
Definition command_sender.h:781
void changePosition(double scale)
Definition command_sender.h:775
void off()
Definition command_sender.h:770
void on()
Definition command_sender.h:765
Definition command_sender.h:689
void setZero() override
Definition command_sender.h:711
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:691
void setLgeLength(double length)
Definition command_sender.h:699
bool getJump()
Definition command_sender.h:703
double getLgeLength()
Definition command_sender.h:707
void setJump(bool jump)
Definition command_sender.h:695
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:939
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:953
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:941
int getMode()
Definition command_sender.h:949
void setZero() override
Definition command_sender.h:963
void setMode(int mode)
Definition command_sender.h:945
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:386
void setShootFrequency(uint8_t mode)
Definition command_sender.h:611
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:453
void setZero() override
Definition command_sender.h:619
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:433
void sendCommand(const ros::Time &time) override
Definition command_sender.h:506
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:449
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:542
uint8_t getShootFrequency()
Definition command_sender.h:615
void setDeployState(bool flag)
Definition command_sender.h:530
void setHeroState(bool flag)
Definition command_sender.h:534
void dropSpeed()
Definition command_sender.h:593
int getShootMode()
Definition command_sender.h:622
double getBackWheelSpeedOffset()
Definition command_sender.h:588
void updateRefereeStatus(bool status)
Definition command_sender.h:437
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:388
double getFrontWheelSpeedOffset()
Definition command_sender.h:583
double getWheelSpeedDes()
Definition command_sender.h:519
~ShooterCommandSender()
Definition command_sender.h:424
void raiseSpeed()
Definition command_sender.h:600
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:429
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:457
void setArmorType(uint8_t armor_type)
Definition command_sender.h:607
double getSpeed()
Definition command_sender.h:514
void checkError(const ros::Time &time)
Definition command_sender.h:479
HeatLimit * heat_limit_
Definition command_sender.h:620
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:441
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:445
bool getDeployState()
Definition command_sender.h:538
Definition command_sender.h:122
void sendCommand(const ros::Time &time) override
Definition command_sender.h:127
TimeStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:124
Definition command_sender.h:653
void setUseLio(bool flag)
Definition command_sender.h:659
void setZero() override
Definition command_sender.h:667
bool getUseLio() const
Definition command_sender.h:663
UseLioCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:655
Definition command_sender.h:149
ros::Subscriber chassis_power_limit_subscriber_
Definition command_sender.h:225
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:173
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
Definition command_sender.h:216
void setAngularZVel(double scale, double limit)
Definition command_sender.h:193
void setLinearYVel(double scale)
Definition command_sender.h:181
void setAngularZVel(double scale)
Definition command_sender.h:185
void setLinearXVel(double scale)
Definition command_sender.h:177
void set2DVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:202
double target_vel_yaw_threshold_
Definition command_sender.h:223
rm_msgs::TrackData track_data_
Definition command_sender.h:226
LinearInterp max_linear_x_
Definition command_sender.h:221
LinearInterp max_linear_y_
Definition command_sender.h:221
double vel_direction_
Definition command_sender.h:224
LinearInterp max_angular_z_
Definition command_sender.h:221
double power_limit_
Definition command_sender.h:222
void setZero() override
Definition command_sender.h:208
Vel2DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:151
Definition command_sender.h:715
void setZero() override
Definition command_sender.h:744
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:717
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:738
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:732
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44