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(
"follow_source_frame", follow_source_frame_))
237 ROS_ERROR(
"follow_source_frame no defined (namespace: %s)", nh.getNamespace().c_str());
239 msg_.follow_source_frame = follow_source_frame_;
240 if (!nh.getParam(
"accel_x", xml_rpc_value))
241 ROS_ERROR(
"Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
243 accel_x_.
init(xml_rpc_value);
244 if (!nh.getParam(
"accel_y", xml_rpc_value))
245 ROS_ERROR(
"Accel Y no defined (namespace: %s)", nh.getNamespace().c_str());
247 accel_y_.
init(xml_rpc_value);
248 if (!nh.getParam(
"accel_z", xml_rpc_value))
249 ROS_ERROR(
"Accel Z no defined (namespace: %s)", nh.getNamespace().c_str());
251 accel_z_.
init(xml_rpc_value);
276 msg_.follow_vel_des = follow_vel_des;
280 follow_source_frame_ = std::move(follow_source_frame);
281 msg_.follow_source_frame = follow_source_frame_;
285 msg_.wireless_state = state;
300 std::string follow_source_frame_;
309 nh.param(
"leg_feedforward_duration", leg_feedforward_duration_, 20.0);
313 leg_switch_time_ = leg_switch_time;
321 msg_.feedforward_countdown =
322 std::max(0,
static_cast<int>(leg_feedforward_duration_ - (ros::Time::now() - leg_switch_time_).toSec()));
328 msg_.feedforward_countdown = 0;
332 double leg_feedforward_duration_{};
333 ros::Time leg_switch_time_{};
340 if (!nh.getParam(
"max_yaw_vel", max_yaw_vel_))
341 ROS_ERROR(
"Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
342 if (!nh.getParam(
"max_pitch_vel", max_pitch_vel_))
343 ROS_ERROR(
"Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
344 if (!nh.getParam(
"time_constant_rc", time_constant_rc_))
345 ROS_ERROR(
"Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
346 if (!nh.getParam(
"time_constant_pc", time_constant_pc_))
347 ROS_ERROR(
"Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
348 if (!nh.getParam(
"track_timeout", track_timeout_))
349 ROS_ERROR(
"Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
350 if (!nh.getParam(
"eject_sensitivity", eject_sensitivity_))
351 eject_sensitivity_ = 1.;
354 void setRate(
double scale_yaw,
double scale_pitch)
356 if (std::abs(scale_yaw) > 1)
357 scale_yaw = scale_yaw > 0 ? 1 : -1;
358 if (std::abs(scale_pitch) > 1)
359 scale_pitch = scale_pitch > 0 ? 1 : -1;
360 double time_constant{};
362 time_constant = time_constant_rc_;
364 time_constant = time_constant_pc_;
365 msg_.rate_yaw =
msg_.rate_yaw + (scale_yaw * max_yaw_vel_ -
msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
367 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ -
msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
370 msg_.rate_yaw *= eject_sensitivity_;
371 msg_.rate_pitch *= eject_sensitivity_;
376 msg_.traj_yaw = traj_yaw;
377 msg_.traj_pitch = traj_pitch;
381 msg_.traj_frame_id = traj_frame_id;
386 msg_.rate_pitch = 0.;
390 msg_.bullet_speed = bullet_speed;
406 msg_.target_pos = point;
410 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
411 double time_constant_rc_{}, time_constant_pc_{};
412 bool eject_flag_{}, use_rc_{};
420 ros::NodeHandle limit_nh(nh,
"heat_limit");
422 nh.param(
"speed_10m_per_speed", speed_10_, 10.);
423 nh.param(
"speed_15m_per_speed", speed_15_, 15.);
424 nh.param(
"speed_16m_per_speed", speed_16_, 16.);
425 nh.param(
"speed_18m_per_speed", speed_18_, 18.);
426 nh.param(
"speed_30m_per_speed", speed_30_, 30.);
427 nh.getParam(
"wheel_speed_10", wheel_speed_10_);
428 nh.getParam(
"wheel_speed_15", wheel_speed_15_);
429 nh.getParam(
"wheel_speed_16", wheel_speed_16_);
430 nh.getParam(
"wheel_speed_18", wheel_speed_18_);
431 nh.getParam(
"wheel_speed_30", wheel_speed_30_);
432 nh.param(
"wheel_speed_offset_front", wheel_speed_offset_front_, 0.0);
433 nh.param(
"wheel_speed_offset_normal", wheel_speed_offset_normal_, 0.0);
434 nh.param(
"wheel_speed_offset_deploy", wheel_speed_offset_deploy_, 0.0);
435 nh.param(
"speed_oscillation", speed_oscillation_, 1.0);
436 nh.param(
"extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
437 nh.param(
"deploy_wheel_speed", deploy_wheel_speed_, 410.0);
438 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
439 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
440 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
442 target_acceleration_tolerance_ = 0.;
443 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
445 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
446 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
447 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
448 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
449 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
451 max_track_target_vel_ = 9.0;
452 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
474 gimbal_des_error_ = error;
478 shoot_beforehand_cmd_ = data;
486 suggest_fire_ = data;
491 if (auto_wheel_speed_)
493 if (last_bullet_speed_ == 0.0)
494 last_bullet_speed_ = speed_des_;
495 if (shoot_data_.bullet_speed != last_bullet_speed_)
497 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
499 total_extra_wheel_speed_ -= 5.0;
501 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
503 total_extra_wheel_speed_ += 5.0;
506 if (shoot_data_.bullet_speed != 0.0)
507 last_bullet_speed_ = shoot_data_.bullet_speed;
512 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
514 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
516 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
518 setMode(rm_msgs::ShootCmd::READY);
522 double gimbal_error_tolerance;
523 if (track_data_.id == 12)
524 gimbal_error_tolerance = track_buff_error_tolerance_;
525 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
526 gimbal_error_tolerance = track_armor_error_tolerance_;
528 gimbal_error_tolerance = untrack_armor_error_tolerance_;
529 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
530 (track_data_.accel > target_acceleration_tolerance_)) ||
531 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
532 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
534 setMode(rm_msgs::ShootCmd::READY);
557 return deploy_wheel_speed_;
558 return wheel_speed_des_;
560 return wheel_speed_des_ + total_extra_wheel_speed_;
578 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
581 speed_des_ = speed_10_;
582 wheel_speed_des_ = wheel_speed_10_;
585 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
588 speed_des_ = speed_15_;
589 wheel_speed_des_ = wheel_speed_15_;
592 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
595 speed_des_ = speed_16_;
596 wheel_speed_des_ = wheel_speed_16_;
599 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
602 speed_des_ = speed_18_;
603 wheel_speed_des_ = wheel_speed_18_;
606 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
609 speed_des_ = speed_30_;
610 wheel_speed_des_ = wheel_speed_30_;
617 allow_deploy_fire_ = flag;
621 return allow_deploy_fire_;
625 wheels_speed_offset_front_ = wheel_speed_offset_front_;
626 return wheels_speed_offset_front_;
631 wheels_speed_offset_back_ = wheel_speed_offset_deploy_;
633 wheels_speed_offset_back_ = wheel_speed_offset_normal_;
634 return wheels_speed_offset_back_;
639 wheel_speed_offset_front_ -= extra_wheel_speed_once_;
641 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
646 wheel_speed_offset_front_ += extra_wheel_speed_once_;
648 total_extra_wheel_speed_ += extra_wheel_speed_once_;
652 armor_type_ = armor_type;
671 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
672 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
673 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
674 double wheel_speed_offset_normal_{}, wheel_speed_offset_deploy_{};
675 double wheel_speed_offset_front_{};
676 double wheels_speed_offset_front_{}, wheels_speed_offset_back_{};
677 double track_armor_error_tolerance_{};
678 double track_buff_error_tolerance_{};
679 double untrack_armor_error_tolerance_{};
680 double max_track_target_vel_{};
681 double target_acceleration_tolerance_{};
682 double extra_wheel_speed_once_{};
683 double total_extra_wheel_speed_{};
684 double deploy_wheel_speed_{};
685 bool auto_wheel_speed_ =
false;
687 bool deploy_flag_ =
false;
688 bool allow_deploy_fire_ =
false;
689 rm_msgs::TrackData track_data_;
690 rm_msgs::GimbalDesError gimbal_des_error_;
691 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
692 rm_msgs::ShootData shoot_data_;
693 std_msgs::Bool suggest_fire_;
694 uint8_t armor_type_{};
746 msg_.leg_length = length;
754 return msg_.leg_length;
764 if (!nh.getParam(
"max_linear_x", max_linear_x_))
765 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
766 if (!nh.getParam(
"max_linear_y", max_linear_y_))
767 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
768 if (!nh.getParam(
"max_linear_z", max_linear_z_))
769 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
770 if (!nh.getParam(
"max_angular_x", max_angular_x_))
771 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
772 if (!nh.getParam(
"max_angular_y", max_angular_y_))
773 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
774 if (!nh.getParam(
"max_angular_z", max_angular_z_))
775 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
779 msg_.twist.linear.x = max_linear_x_ * scale_x;
780 msg_.twist.linear.y = max_linear_y_ * scale_y;
781 msg_.twist.linear.z = max_linear_z_ * scale_z;
785 msg_.twist.angular.x = max_angular_x_ * scale_x;
786 msg_.twist.angular.y = max_angular_y_ * scale_y;
787 msg_.twist.angular.z = max_angular_z_ * scale_z;
791 msg_.twist.linear.x = 0.;
792 msg_.twist.linear.y = 0.;
793 msg_.twist.linear.z = 0.;
794 msg_.twist.angular.x = 0.;
795 msg_.twist.angular.y = 0.;
796 msg_.twist.angular.z = 0.;
800 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
808 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
817 msg_.data = off_pos_;
822 current_position_ =
msg_.data;
823 change_position_ = current_position_ + scale * per_change_position_;
824 msg_.data = change_position_;
838 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
846 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
847 nh.getParam(
"off_pos", off_pos_));
851 msg_.data = long_pos_;
856 msg_.data = short_pos_;
861 msg_.data = off_pos_;
876 double long_pos_{}, short_pos_{}, off_pos_{};
885 ROS_ASSERT(nh.getParam(
"joint", joint_));
886 ROS_ASSERT(nh.getParam(
"step", step_));
890 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
891 if (i != joint_state_.name.end())
892 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
898 if (
msg_.data != NAN)
906 if (
msg_.data != NAN)
918 std::string joint_{};
919 const sensor_msgs::JointState& joint_state_;
929 ROS_ASSERT(nh.getParam(
"joint", joint_));
937 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
938 if (i != joint_state_.name.end())
940 index_ = std::distance(joint_state_.name.begin(), i);
945 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
952 std::string joint_{};
954 const sensor_msgs::JointState& joint_state_;
962 ROS_ASSERT(nh.getParam(
"camera_left_name", camera1_name_) && nh.getParam(
"camera_right_name", camera2_name_));
963 msg_.data = camera2_name_;
967 msg_.data = camera1_name_;
971 msg_.data = camera2_name_;
980 std::string camera1_name_{}, camera2_name_{};
998 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
1001 msg_.linear.x = linear_x;
1002 msg_.linear.y = linear_y;
1003 msg_.linear.z = linear_z;
1004 msg_.angular.x = angular_x;
1005 msg_.angular.y = angular_y;
1006 msg_.angular.z = angular_z;
1027 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
1029 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
1031 ros::NodeHandle barrel_nh(nh,
"barrel");
1034 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
1035 barrel_nh.getParam(
"id1_point", id1_point_);
1036 barrel_nh.getParam(
"id2_point", id2_point_);
1037 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
1038 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
1039 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
1040 barrel_nh.getParam(
"ready_duration", ready_duration_);
1041 barrel_nh.getParam(
"switching_duration", switching_duration_);
1043 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
1044 &DoubleBarrelCommandSender::jointStateCallback,
this);
1045 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
1046 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
1100 need_switch_ =
true;
1104 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1105 last_push_time_ = time;
1110 ros::Time time = ros::Time::now();
1111 barrel_command_sender_->
setPoint(id1_point_);
1112 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1113 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1139 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1143 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1147 ros::Time time = ros::Time::now();
1148 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1149 setMode(rm_msgs::ShootCmd::READY);
1150 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1152 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1153 barrel_command_sender_->
setPoint(id2_point_);
1155 last_switch_time_ = time;
1156 need_switch_ =
false;
1157 is_switching_ =
true;
1163 ros::Time time = ros::Time::now();
1166 setMode(rm_msgs::ShootCmd::READY);
1167 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1168 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1169 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1170 is_switching_ =
false;
1176 if (!is_double_barrel_)
1181 ROS_WARN_ONCE(
"Can not get cooling limit");
1187 if (getBarrel() == shooter_ID1_cmd_sender_)
1197 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1199 trigger_error_ = data->error;
1201 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1203 joint_state_ = *data;
1205 ShooterCommandSender* shooter_ID1_cmd_sender_;
1206 ShooterCommandSender* shooter_ID2_cmd_sender_;
1207 JointPointCommandSender* barrel_command_sender_{};
1208 ros::Subscriber trigger_state_sub_;
1209 ros::Subscriber joint_state_sub_;
1210 sensor_msgs::JointState joint_state_;
1211 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1212 ros::Time last_switch_time_, last_push_time_;
1213 double ready_duration_, switching_duration_;
1214 double trigger_error_;
1215 bool is_id1_{
false };
1216 double id1_point_, id2_point_;
1217 double frequency_threshold_;
1218 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:716
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:718
int getBalanceMode()
Definition command_sender.h:726
void setZero() override
Definition command_sender.h:730
void setBalanceMode(const int mode)
Definition command_sender.h:722
Definition command_sender.h:698
bool getBallisticSolverRequest() const
Definition command_sender.h:708
BallisticSolverRequestCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:700
void setZero() override
Definition command_sender.h:712
void setBallisticSolverRequest(bool flag)
Definition command_sender.h:704
Definition command_sender.h:958
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:960
void setZero() override
Definition command_sender.h:977
void switchCameraRight()
Definition command_sender.h:969
void switchCameraLeft()
Definition command_sender.h:965
void sendCommand(const ros::Time &time) override
Definition command_sender.h:973
Definition command_sender.h:842
void long_on()
Definition command_sender.h:849
void off()
Definition command_sender.h:859
void sendCommand(const ros::Time &time) override
Definition command_sender.h:868
void setZero() override
Definition command_sender.h:872
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:844
bool getState() const
Definition command_sender.h:864
void short_on()
Definition command_sender.h:854
Definition command_sender.h:304
void sendCommand(const ros::Time &time) override
Definition command_sender.h:319
int getLegMode()
Definition command_sender.h:315
void setZero() override
Definition command_sender.h:325
void setLegSwitchTime(ros::Time leg_switch_time)
Definition command_sender.h:311
ChassisActiveSuspensionCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:306
Definition command_sender.h:230
void setFollowVelDes(double follow_vel_des)
Definition command_sender.h:274
void updateRefereeStatus(bool status)
Definition command_sender.h:270
void setFollowSourceFrame(std::string follow_source_frame)
Definition command_sender.h:278
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:258
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition command_sender.h:287
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition command_sender.h:266
ChassisCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:232
PowerLimit * power_limit_
Definition command_sender.h:296
void setZero() override
Definition command_sender.h:295
void setWirelessState(bool state)
Definition command_sender.h:283
void updateSafetyPower(int safety_power)
Definition command_sender.h:254
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:262
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:1023
void setZero()
Definition command_sender.h:1089
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:1025
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:1069
double getSpeed()
Definition command_sender.h:1131
void setMode(int mode)
Definition command_sender.h:1085
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:1074
void sendCommand(const ros::Time &time)
Definition command_sender.h:1097
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:1064
void init()
Definition command_sender.h:1108
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:1079
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:1049
void updateRefereeStatus(bool status)
Definition command_sender.h:1059
void setShootFrequency(uint8_t mode)
Definition command_sender.h:1123
void setArmorType(uint8_t armor_type)
Definition command_sender.h:1118
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:1054
uint8_t getShootFrequency()
Definition command_sender.h:1127
void checkError(const ros::Time &time)
Definition command_sender.h:1093
Definition command_sender.h:336
void setGimbalTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:379
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:354
~GimbalCommandSender()=default
bool getEject() const
Definition command_sender.h:400
void setUseRc(bool flag)
Definition command_sender.h:396
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:388
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:404
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:374
void setEject(bool flag)
Definition command_sender.h:392
void setZero() override
Definition command_sender.h:383
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:338
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:180
double getShootFrequency() const
Definition heat_limit.h:147
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:119
void setRefereeStatus(bool status)
Definition heat_limit.h:142
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:190
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:168
bool getShootFrequencyMode() const
Definition heat_limit.h:195
Definition command_sender.h:880
void reset()
Definition command_sender.h:888
const std::string & getJoint()
Definition command_sender.h:912
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:882
void minus()
Definition command_sender.h:904
void plus()
Definition command_sender.h:896
Definition command_sender.h:924
int getIndex()
Definition command_sender.h:935
void setZero() override
Definition command_sender.h:949
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:926
void setPoint(double point)
Definition command_sender.h:931
Definition command_sender.h:804
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:806
void sendCommand(const ros::Time &time) override
Definition command_sender.h:830
void setZero() override
Definition command_sender.h:834
bool getState() const
Definition command_sender.h:826
void changePosition(double scale)
Definition command_sender.h:820
void off()
Definition command_sender.h:815
void on()
Definition command_sender.h:810
Definition command_sender.h:734
void setZero() override
Definition command_sender.h:756
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:736
void setLgeLength(double length)
Definition command_sender.h:744
bool getJump()
Definition command_sender.h:748
double getLgeLength()
Definition command_sender.h:752
void setJump(bool jump)
Definition command_sender.h:740
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:984
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:998
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:986
int getMode()
Definition command_sender.h:994
void setZero() override
Definition command_sender.h:1008
void setMode(int mode)
Definition command_sender.h:990
Definition power_limit.h:53
void setRefereeStatus(bool status)
Definition power_limit.h:123
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:117
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:113
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:108
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:186
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition command_sender.h:416
void setDeployAllowFireFlag(bool flag)
Definition command_sender.h:615
void setShootFrequency(uint8_t mode)
Definition command_sender.h:654
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:484
void setZero() override
Definition command_sender.h:662
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:464
void sendCommand(const ros::Time &time) override
Definition command_sender.h:537
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:480
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:574
uint8_t getShootFrequency()
Definition command_sender.h:658
void setDeployState(bool flag)
Definition command_sender.h:562
void setHeroState(bool flag)
Definition command_sender.h:566
void dropSpeed()
Definition command_sender.h:636
int getShootMode()
Definition command_sender.h:665
double getBackWheelSpeedOffset()
Definition command_sender.h:628
void updateRefereeStatus(bool status)
Definition command_sender.h:468
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:418
double getFrontWheelSpeedOffset()
Definition command_sender.h:623
double getWheelSpeedDes()
Definition command_sender.h:551
~ShooterCommandSender()
Definition command_sender.h:455
void raiseSpeed()
Definition command_sender.h:643
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:460
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:488
void setArmorType(uint8_t armor_type)
Definition command_sender.h:650
double getSpeed()
Definition command_sender.h:546
void checkError(const ros::Time &time)
Definition command_sender.h:510
bool getDeployAllowFireFlag()
Definition command_sender.h:619
HeatLimit * heat_limit_
Definition command_sender.h:663
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:472
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:476
bool getDeployState()
Definition command_sender.h:570
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: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:760
void setZero() override
Definition command_sender.h:789
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:762
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:783
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:777
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44