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 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
387 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
388 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
390 target_acceleration_tolerance_ = 0.;
391 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
393 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
394 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
395 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
396 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
397 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
399 max_track_target_vel_ = 9.0;
400 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
422 gimbal_des_error_ = error;
426 shoot_beforehand_cmd_ = data;
434 suggest_fire_ = data;
439 if (auto_wheel_speed_)
441 if (last_bullet_speed_ == 0.0)
442 last_bullet_speed_ = speed_des_;
443 if (shoot_data_.bullet_speed != last_bullet_speed_)
445 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
447 total_extra_wheel_speed_ -= 5.0;
449 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
451 total_extra_wheel_speed_ += 5.0;
454 if (shoot_data_.bullet_speed != 0.0)
455 last_bullet_speed_ = shoot_data_.bullet_speed;
460 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
462 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
464 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
466 setMode(rm_msgs::ShootCmd::READY);
470 double gimbal_error_tolerance;
471 if (track_data_.id == 12)
472 gimbal_error_tolerance = track_buff_error_tolerance_;
473 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
474 gimbal_error_tolerance = track_armor_error_tolerance_;
476 gimbal_error_tolerance = untrack_armor_error_tolerance_;
477 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
478 (track_data_.accel > target_acceleration_tolerance_)) ||
479 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
480 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
481 setMode(rm_msgs::ShootCmd::READY);
497 return wheel_speed_des_ + total_extra_wheel_speed_;
503 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
506 speed_des_ = speed_10_;
507 wheel_speed_des_ = wheel_speed_10_;
510 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
513 speed_des_ = speed_15_;
514 wheel_speed_des_ = wheel_speed_15_;
517 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
520 speed_des_ = speed_16_;
521 wheel_speed_des_ = wheel_speed_16_;
524 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
527 speed_des_ = speed_18_;
528 wheel_speed_des_ = wheel_speed_18_;
531 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
534 speed_des_ = speed_30_;
535 wheel_speed_des_ = wheel_speed_30_;
542 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
546 total_extra_wheel_speed_ += extra_wheel_speed_once_;
550 armor_type_ = armor_type;
564 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
565 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
566 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
567 double track_armor_error_tolerance_{};
568 double track_buff_error_tolerance_{};
569 double untrack_armor_error_tolerance_{};
570 double max_track_target_vel_{};
571 double target_acceleration_tolerance_{};
572 double extra_wheel_speed_once_{};
573 double total_extra_wheel_speed_{};
574 bool auto_wheel_speed_ =
false;
575 rm_msgs::TrackData track_data_;
576 rm_msgs::GimbalDesError gimbal_des_error_;
577 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
578 rm_msgs::ShootData shoot_data_;
579 std_msgs::Bool suggest_fire_;
580 uint8_t armor_type_{};
614 msg_.leg_length = length;
622 return msg_.leg_length;
632 if (!nh.getParam(
"max_linear_x", max_linear_x_))
633 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
634 if (!nh.getParam(
"max_linear_y", max_linear_y_))
635 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
636 if (!nh.getParam(
"max_linear_z", max_linear_z_))
637 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
638 if (!nh.getParam(
"max_angular_x", max_angular_x_))
639 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
640 if (!nh.getParam(
"max_angular_y", max_angular_y_))
641 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
642 if (!nh.getParam(
"max_angular_z", max_angular_z_))
643 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
647 msg_.twist.linear.x = max_linear_x_ * scale_x;
648 msg_.twist.linear.y = max_linear_y_ * scale_y;
649 msg_.twist.linear.z = max_linear_z_ * scale_z;
653 msg_.twist.angular.x = max_angular_x_ * scale_x;
654 msg_.twist.angular.y = max_angular_y_ * scale_y;
655 msg_.twist.angular.z = max_angular_z_ * scale_z;
659 msg_.twist.linear.x = 0.;
660 msg_.twist.linear.y = 0.;
661 msg_.twist.linear.z = 0.;
662 msg_.twist.angular.x = 0.;
663 msg_.twist.angular.y = 0.;
664 msg_.twist.angular.z = 0.;
668 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
676 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
685 msg_.data = off_pos_;
690 current_position_ =
msg_.data;
691 change_position_ = current_position_ + scale * per_change_position_;
692 msg_.data = change_position_;
706 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
714 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
715 nh.getParam(
"off_pos", off_pos_));
719 msg_.data = long_pos_;
724 msg_.data = short_pos_;
729 msg_.data = off_pos_;
744 double long_pos_{}, short_pos_{}, off_pos_{};
753 ROS_ASSERT(nh.getParam(
"joint", joint_));
754 ROS_ASSERT(nh.getParam(
"step", step_));
758 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
759 if (i != joint_state_.name.end())
760 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
766 if (
msg_.data != NAN)
774 if (
msg_.data != NAN)
786 std::string joint_{};
787 const sensor_msgs::JointState& joint_state_;
797 ROS_ASSERT(nh.getParam(
"joint", joint_));
805 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
806 if (i != joint_state_.name.end())
808 index_ = std::distance(joint_state_.name.begin(), i);
813 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
820 std::string joint_{};
822 const sensor_msgs::JointState& joint_state_;
830 ROS_ASSERT(nh.getParam(
"camera1_name", camera1_name_) && nh.getParam(
"camera2_name", camera2_name_));
831 msg_.data = camera1_name_;
835 msg_.data =
msg_.data == camera1_name_ ? camera2_name_ : camera1_name_;
844 std::string camera1_name_{}, camera2_name_{};
862 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
865 msg_.linear.x = linear_x;
866 msg_.linear.y = linear_y;
867 msg_.linear.z = linear_z;
868 msg_.angular.x = angular_x;
869 msg_.angular.y = angular_y;
870 msg_.angular.z = angular_z;
862 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y, {
…}
891 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
893 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
895 ros::NodeHandle barrel_nh(nh,
"barrel");
898 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
899 barrel_nh.getParam(
"id1_point", id1_point_);
900 barrel_nh.getParam(
"id2_point", id2_point_);
901 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
902 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
903 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
904 barrel_nh.getParam(
"ready_duration", ready_duration_);
905 barrel_nh.getParam(
"switching_duration", switching_duration_);
907 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
908 &DoubleBarrelCommandSender::jointStateCallback,
this);
909 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
910 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
968 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
969 last_push_time_ = time;
974 ros::Time time = ros::Time::now();
975 barrel_command_sender_->
setPoint(id1_point_);
976 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
977 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1003 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1007 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1011 ros::Time time = ros::Time::now();
1012 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1013 setMode(rm_msgs::ShootCmd::READY);
1014 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1016 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1017 barrel_command_sender_->
setPoint(id2_point_);
1019 last_switch_time_ = time;
1020 need_switch_ =
false;
1021 is_switching_ =
true;
1027 ros::Time time = ros::Time::now();
1030 setMode(rm_msgs::ShootCmd::READY);
1031 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1032 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1033 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1034 is_switching_ =
false;
1040 if (!is_double_barrel_)
1045 ROS_WARN_ONCE(
"Can not get cooling limit");
1051 if (getBarrel() == shooter_ID1_cmd_sender_)
1061 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1063 trigger_error_ = data->error;
1065 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1067 joint_state_ = *data;
1069 ShooterCommandSender* shooter_ID1_cmd_sender_;
1070 ShooterCommandSender* shooter_ID2_cmd_sender_;
1071 JointPointCommandSender* barrel_command_sender_{};
1072 ros::Subscriber trigger_state_sub_;
1073 ros::Subscriber joint_state_sub_;
1074 sensor_msgs::JointState joint_state_;
1075 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1076 ros::Time last_switch_time_, last_push_time_;
1077 double ready_duration_, switching_duration_;
1078 double trigger_error_;
1079 bool is_id1_{
false };
1080 double id1_point_, id2_point_;
1081 double frequency_threshold_;
1082 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:584
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:586
int getBalanceMode()
Definition command_sender.h:594
void setZero() override
Definition command_sender.h:598
void setBalanceMode(const int mode)
Definition command_sender.h:590
Definition command_sender.h:826
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:828
void setZero() override
Definition command_sender.h:841
void switchCamera()
Definition command_sender.h:833
void sendCommand(const ros::Time &time) override
Definition command_sender.h:837
Definition command_sender.h:710
void long_on()
Definition command_sender.h:717
void off()
Definition command_sender.h:727
void sendCommand(const ros::Time &time) override
Definition command_sender.h:736
void setZero() override
Definition command_sender.h:740
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:712
bool getState() const
Definition command_sender.h:732
void short_on()
Definition command_sender.h:722
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:887
void setZero()
Definition command_sender.h:953
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:889
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:933
double getSpeed()
Definition command_sender.h:995
void setMode(int mode)
Definition command_sender.h:949
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:938
void sendCommand(const ros::Time &time)
Definition command_sender.h:961
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:928
void init()
Definition command_sender.h:972
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:943
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:913
void updateRefereeStatus(bool status)
Definition command_sender.h:923
void setShootFrequency(uint8_t mode)
Definition command_sender.h:987
void setArmorType(uint8_t armor_type)
Definition command_sender.h:982
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:918
uint8_t getShootFrequency()
Definition command_sender.h:991
void checkError(const ros::Time &time)
Definition command_sender.h:957
Definition command_sender.h:288
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 setGimbalTrajFrameId(std::string traj_frame_id)
Definition command_sender.h:331
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:50
int getCoolingLimit()
Definition heat_limit.h:162
double getShootFrequency() const
Definition heat_limit.h:132
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:105
void setRefereeStatus(bool status)
Definition heat_limit.h:127
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:172
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:111
int getSpeedLimit()
Definition heat_limit.h:150
bool getShootFrequencyMode() const
Definition heat_limit.h:177
Definition command_sender.h:748
void reset()
Definition command_sender.h:756
const std::string & getJoint()
Definition command_sender.h:780
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:750
void minus()
Definition command_sender.h:772
void plus()
Definition command_sender.h:764
Definition command_sender.h:792
int getIndex()
Definition command_sender.h:803
void setZero() override
Definition command_sender.h:817
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:794
void setPoint(double point)
Definition command_sender.h:799
Definition command_sender.h:672
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:674
void sendCommand(const ros::Time &time) override
Definition command_sender.h:698
void setZero() override
Definition command_sender.h:702
bool getState() const
Definition command_sender.h:694
void changePosition(double scale)
Definition command_sender.h:688
void off()
Definition command_sender.h:683
void on()
Definition command_sender.h:678
Definition command_sender.h:602
void setZero() override
Definition command_sender.h:624
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:604
void setLgeLength(double length)
Definition command_sender.h:612
bool getJump()
Definition command_sender.h:616
double getLgeLength()
Definition command_sender.h:620
void setJump(bool jump)
Definition command_sender.h:608
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:848
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:862
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:850
int getMode()
Definition command_sender.h:858
void setZero() override
Definition command_sender.h:872
void setMode(int mode)
Definition command_sender.h:854
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:552
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:432
void setZero() override
Definition command_sender.h:560
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:412
void sendCommand(const ros::Time &time) override
Definition command_sender.h:483
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:428
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:499
uint8_t getShootFrequency()
Definition command_sender.h:556
void dropSpeed()
Definition command_sender.h:540
void updateRefereeStatus(bool status)
Definition command_sender.h:416
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:370
double getWheelSpeedDes()
Definition command_sender.h:494
~ShooterCommandSender()
Definition command_sender.h:403
void raiseSpeed()
Definition command_sender.h:544
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:408
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:436
void setArmorType(uint8_t armor_type)
Definition command_sender.h:548
double getSpeed()
Definition command_sender.h:489
void checkError(const ros::Time &time)
Definition command_sender.h:458
HeatLimit * heat_limit_
Definition command_sender.h:561
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:420
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:424
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:628
void setZero() override
Definition command_sender.h:657
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:630
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:651
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:645
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44