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)
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;
292 if (!nh.getParam(
"max_yaw_vel", max_yaw_vel_))
293 ROS_ERROR(
"Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
294 if (!nh.getParam(
"max_pitch_vel", max_pitch_vel_))
295 ROS_ERROR(
"Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
296 if (!nh.getParam(
"time_constant_rc", time_constant_rc_))
297 ROS_ERROR(
"Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
298 if (!nh.getParam(
"time_constant_pc", time_constant_pc_))
299 ROS_ERROR(
"Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
300 if (!nh.getParam(
"track_timeout", track_timeout_))
301 ROS_ERROR(
"Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
302 if (!nh.getParam(
"eject_sensitivity", eject_sensitivity_))
303 eject_sensitivity_ = 1.;
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{};
314 time_constant = time_constant_rc_;
316 time_constant = time_constant_pc_;
317 msg_.rate_yaw =
msg_.rate_yaw + (scale_yaw * max_yaw_vel_ -
msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
319 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ -
msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
322 msg_.rate_yaw *= eject_sensitivity_;
323 msg_.rate_pitch *= eject_sensitivity_;
306 void setRate(
double scale_yaw,
double scale_pitch) {
…}
328 msg_.traj_yaw = traj_yaw;
329 msg_.traj_pitch = traj_pitch;
333 msg_.traj_frame_id = traj_frame_id;
338 msg_.rate_pitch = 0.;
342 msg_.bullet_speed = bullet_speed;
358 msg_.target_pos = point;
362 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
363 double time_constant_rc_{}, time_constant_pc_{};
364 bool eject_flag_{}, use_rc_{};
372 ros::NodeHandle limit_nh(nh,
"heat_limit");
374 nh.param(
"speed_10m_per_speed", speed_10_, 10.);
375 nh.param(
"speed_15m_per_speed", speed_15_, 15.);
376 nh.param(
"speed_16m_per_speed", speed_16_, 16.);
377 nh.param(
"speed_18m_per_speed", speed_18_, 18.);
378 nh.param(
"speed_30m_per_speed", speed_30_, 30.);
379 nh.getParam(
"wheel_speed_10", wheel_speed_10_);
380 nh.getParam(
"wheel_speed_15", wheel_speed_15_);
381 nh.getParam(
"wheel_speed_16", wheel_speed_16_);
382 nh.getParam(
"wheel_speed_18", wheel_speed_18_);
383 nh.getParam(
"wheel_speed_30", wheel_speed_30_);
384 nh.param(
"speed_oscillation", speed_oscillation_, 1.0);
385 nh.param(
"extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
386 nh.param(
"deploy_wheel_speed", deploy_wheel_speed_, 410.0);
387 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
388 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
389 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
391 target_acceleration_tolerance_ = 0.;
392 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
394 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
395 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
396 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
397 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
398 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
400 max_track_target_vel_ = 9.0;
401 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
423 gimbal_des_error_ = error;
427 shoot_beforehand_cmd_ = data;
435 suggest_fire_ = data;
440 if (auto_wheel_speed_)
442 if (last_bullet_speed_ == 0.0)
443 last_bullet_speed_ = speed_des_;
444 if (shoot_data_.bullet_speed != last_bullet_speed_)
446 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
448 total_extra_wheel_speed_ -= 5.0;
450 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
452 total_extra_wheel_speed_ += 5.0;
455 if (shoot_data_.bullet_speed != 0.0)
456 last_bullet_speed_ = shoot_data_.bullet_speed;
461 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
463 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
465 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
467 setMode(rm_msgs::ShootCmd::READY);
471 double gimbal_error_tolerance;
472 if (track_data_.id == 12)
473 gimbal_error_tolerance = track_buff_error_tolerance_;
474 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
475 gimbal_error_tolerance = track_armor_error_tolerance_;
477 gimbal_error_tolerance = untrack_armor_error_tolerance_;
478 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
479 (track_data_.accel > target_acceleration_tolerance_)) ||
480 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
481 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
482 setMode(rm_msgs::ShootCmd::READY);
500 return deploy_wheel_speed_ + total_extra_wheel_speed_;
502 return wheel_speed_des_ + total_extra_wheel_speed_;
512 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
515 speed_des_ = speed_10_;
516 wheel_speed_des_ = wheel_speed_10_;
519 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
522 speed_des_ = speed_15_;
523 wheel_speed_des_ = wheel_speed_15_;
526 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
529 speed_des_ = speed_16_;
530 wheel_speed_des_ = wheel_speed_16_;
533 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
536 speed_des_ = speed_18_;
537 wheel_speed_des_ = wheel_speed_18_;
540 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
543 speed_des_ = speed_30_;
544 wheel_speed_des_ = wheel_speed_30_;
551 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
555 total_extra_wheel_speed_ += extra_wheel_speed_once_;
559 armor_type_ = armor_type;
573 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
574 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
575 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
576 double track_armor_error_tolerance_{};
577 double track_buff_error_tolerance_{};
578 double untrack_armor_error_tolerance_{};
579 double max_track_target_vel_{};
580 double target_acceleration_tolerance_{};
581 double extra_wheel_speed_once_{};
582 double total_extra_wheel_speed_{};
583 double deploy_wheel_speed_{};
584 bool auto_wheel_speed_ =
false;
586 rm_msgs::TrackData track_data_;
587 rm_msgs::GimbalDesError gimbal_des_error_;
588 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
589 rm_msgs::ShootData shoot_data_;
590 std_msgs::Bool suggest_fire_;
591 uint8_t armor_type_{};
625 msg_.leg_length = length;
633 return msg_.leg_length;
643 if (!nh.getParam(
"max_linear_x", max_linear_x_))
644 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
645 if (!nh.getParam(
"max_linear_y", max_linear_y_))
646 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
647 if (!nh.getParam(
"max_linear_z", max_linear_z_))
648 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
649 if (!nh.getParam(
"max_angular_x", max_angular_x_))
650 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
651 if (!nh.getParam(
"max_angular_y", max_angular_y_))
652 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
653 if (!nh.getParam(
"max_angular_z", max_angular_z_))
654 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
658 msg_.twist.linear.x = max_linear_x_ * scale_x;
659 msg_.twist.linear.y = max_linear_y_ * scale_y;
660 msg_.twist.linear.z = max_linear_z_ * scale_z;
664 msg_.twist.angular.x = max_angular_x_ * scale_x;
665 msg_.twist.angular.y = max_angular_y_ * scale_y;
666 msg_.twist.angular.z = max_angular_z_ * scale_z;
670 msg_.twist.linear.x = 0.;
671 msg_.twist.linear.y = 0.;
672 msg_.twist.linear.z = 0.;
673 msg_.twist.angular.x = 0.;
674 msg_.twist.angular.y = 0.;
675 msg_.twist.angular.z = 0.;
679 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
687 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
696 msg_.data = off_pos_;
701 current_position_ =
msg_.data;
702 change_position_ = current_position_ + scale * per_change_position_;
703 msg_.data = change_position_;
717 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
725 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
726 nh.getParam(
"off_pos", off_pos_));
730 msg_.data = long_pos_;
735 msg_.data = short_pos_;
740 msg_.data = off_pos_;
755 double long_pos_{}, short_pos_{}, off_pos_{};
764 ROS_ASSERT(nh.getParam(
"joint", joint_));
765 ROS_ASSERT(nh.getParam(
"step", step_));
769 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
770 if (i != joint_state_.name.end())
771 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
777 if (
msg_.data != NAN)
785 if (
msg_.data != NAN)
797 std::string joint_{};
798 const sensor_msgs::JointState& joint_state_;
808 ROS_ASSERT(nh.getParam(
"joint", joint_));
816 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
817 if (i != joint_state_.name.end())
819 index_ = std::distance(joint_state_.name.begin(), i);
824 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
831 std::string joint_{};
833 const sensor_msgs::JointState& joint_state_;
841 ROS_ASSERT(nh.getParam(
"camera1_name", camera1_name_) && nh.getParam(
"camera2_name", camera2_name_));
842 msg_.data = camera1_name_;
846 msg_.data =
msg_.data == camera1_name_ ? camera2_name_ : camera1_name_;
855 std::string camera1_name_{}, camera2_name_{};
873 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
876 msg_.linear.x = linear_x;
877 msg_.linear.y = linear_y;
878 msg_.linear.z = linear_z;
879 msg_.angular.x = angular_x;
880 msg_.angular.y = angular_y;
881 msg_.angular.z = angular_z;
873 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y, {
…}
902 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
904 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
906 ros::NodeHandle barrel_nh(nh,
"barrel");
909 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
910 barrel_nh.getParam(
"id1_point", id1_point_);
911 barrel_nh.getParam(
"id2_point", id2_point_);
912 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
913 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
914 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
915 barrel_nh.getParam(
"ready_duration", ready_duration_);
916 barrel_nh.getParam(
"switching_duration", switching_duration_);
918 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
919 &DoubleBarrelCommandSender::jointStateCallback,
this);
920 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
921 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
979 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
980 last_push_time_ = time;
985 ros::Time time = ros::Time::now();
986 barrel_command_sender_->
setPoint(id1_point_);
987 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
988 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1014 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1018 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1022 ros::Time time = ros::Time::now();
1023 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1024 setMode(rm_msgs::ShootCmd::READY);
1025 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1027 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1028 barrel_command_sender_->
setPoint(id2_point_);
1030 last_switch_time_ = time;
1031 need_switch_ =
false;
1032 is_switching_ =
true;
1038 ros::Time time = ros::Time::now();
1041 setMode(rm_msgs::ShootCmd::READY);
1042 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1043 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1044 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1045 is_switching_ =
false;
1051 if (!is_double_barrel_)
1056 ROS_WARN_ONCE(
"Can not get cooling limit");
1062 if (getBarrel() == shooter_ID1_cmd_sender_)
1072 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1074 trigger_error_ = data->error;
1076 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1078 joint_state_ = *data;
1080 ShooterCommandSender* shooter_ID1_cmd_sender_;
1081 ShooterCommandSender* shooter_ID2_cmd_sender_;
1082 JointPointCommandSender* barrel_command_sender_{};
1083 ros::Subscriber trigger_state_sub_;
1084 ros::Subscriber joint_state_sub_;
1085 sensor_msgs::JointState joint_state_;
1086 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1087 ros::Time last_switch_time_, last_push_time_;
1088 double ready_duration_, switching_duration_;
1089 double trigger_error_;
1090 bool is_id1_{
false };
1091 double id1_point_, id2_point_;
1092 double frequency_threshold_;
1093 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:595
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:597
int getBalanceMode()
Definition command_sender.h:605
void setZero() override
Definition command_sender.h:609
void setBalanceMode(const int mode)
Definition command_sender.h:601
Definition command_sender.h:837
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:839
void setZero() override
Definition command_sender.h:852
void switchCamera()
Definition command_sender.h:844
void sendCommand(const ros::Time &time) override
Definition command_sender.h:848
Definition command_sender.h:721
void long_on()
Definition command_sender.h:728
void off()
Definition command_sender.h:738
void sendCommand(const ros::Time &time) override
Definition command_sender.h:747
void setZero() override
Definition command_sender.h:751
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:723
bool getState() const
Definition command_sender.h:743
void short_on()
Definition command_sender.h:733
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:272
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:281
void setZero() override
Definition command_sender.h:280
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:898
void setZero()
Definition command_sender.h:964
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:900
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:944
double getSpeed()
Definition command_sender.h:1006
void setMode(int mode)
Definition command_sender.h:960
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:949
void sendCommand(const ros::Time &time)
Definition command_sender.h:972
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:939
void init()
Definition command_sender.h:983
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:954
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:924
void updateRefereeStatus(bool status)
Definition command_sender.h:934
void setShootFrequency(uint8_t mode)
Definition command_sender.h:998
void setArmorType(uint8_t armor_type)
Definition command_sender.h:993
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:929
uint8_t getShootFrequency()
Definition command_sender.h:1002
void checkError(const ros::Time &time)
Definition command_sender.h:968
Definition command_sender.h:288
void setGimbalTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:331
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:306
~GimbalCommandSender()=default
bool getEject() const
Definition command_sender.h:352
void setUseRc(bool flag)
Definition command_sender.h:348
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:340
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:356
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:326
void setEject(bool flag)
Definition command_sender.h:344
void setZero() override
Definition command_sender.h:335
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:290
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:51
int getCoolingLimit()
Definition heat_limit.h:169
double getShootFrequency() const
Definition heat_limit.h:138
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:111
void setRefereeStatus(bool status)
Definition heat_limit.h:133
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:179
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:117
int getSpeedLimit()
Definition heat_limit.h:157
bool getShootFrequencyMode() const
Definition heat_limit.h:184
Definition command_sender.h:759
void reset()
Definition command_sender.h:767
const std::string & getJoint()
Definition command_sender.h:791
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:761
void minus()
Definition command_sender.h:783
void plus()
Definition command_sender.h:775
Definition command_sender.h:803
int getIndex()
Definition command_sender.h:814
void setZero() override
Definition command_sender.h:828
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:805
void setPoint(double point)
Definition command_sender.h:810
Definition command_sender.h:683
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:685
void sendCommand(const ros::Time &time) override
Definition command_sender.h:709
void setZero() override
Definition command_sender.h:713
bool getState() const
Definition command_sender.h:705
void changePosition(double scale)
Definition command_sender.h:699
void off()
Definition command_sender.h:694
void on()
Definition command_sender.h:689
Definition command_sender.h:613
void setZero() override
Definition command_sender.h:635
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:615
void setLgeLength(double length)
Definition command_sender.h:623
bool getJump()
Definition command_sender.h:627
double getLgeLength()
Definition command_sender.h:631
void setJump(bool jump)
Definition command_sender.h:619
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:859
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:873
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:861
int getMode()
Definition command_sender.h:869
void setZero() override
Definition command_sender.h:883
void setMode(int mode)
Definition command_sender.h:865
Definition power_limit.h:50
void setRefereeStatus(bool status)
Definition power_limit.h:124
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:118
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:151
void updateSafetyPower(int safety_power)
Definition power_limit.h:91
Definition command_sender.h:368
void setShootFrequency(uint8_t mode)
Definition command_sender.h:561
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:433
void setZero() override
Definition command_sender.h:569
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:413
void sendCommand(const ros::Time &time) override
Definition command_sender.h:484
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:429
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:508
uint8_t getShootFrequency()
Definition command_sender.h:565
void setDeployState(bool flag)
Definition command_sender.h:504
void dropSpeed()
Definition command_sender.h:549
void updateRefereeStatus(bool status)
Definition command_sender.h:417
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:370
double getWheelSpeedDes()
Definition command_sender.h:495
~ShooterCommandSender()
Definition command_sender.h:404
void raiseSpeed()
Definition command_sender.h:553
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:409
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:437
void setArmorType(uint8_t armor_type)
Definition command_sender.h:557
double getSpeed()
Definition command_sender.h:490
void checkError(const ros::Time &time)
Definition command_sender.h:459
HeatLimit * heat_limit_
Definition command_sender.h:570
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:421
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:425
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: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:639
void setZero() override
Definition command_sender.h:668
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:641
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:662
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:656
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44