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>
77template <
typename TMsg>
79 ->
decltype((void)(msg.traj_frame_id = traj_frame_id), void())
81 msg.traj_frame_id = traj_frame_id;
84template <
typename TMsg>
90template <
class MsgType>
96 if (!nh.getParam(
"topic",
topic_))
97 ROS_ERROR(
"Topic name no defined (namespace: %s)", nh.getNamespace().c_str());
103 if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
135template <
class MsgType>
149template <
class MsgType>
168 XmlRpc::XmlRpcValue xml_rpc_value;
169 if (!nh.getParam(
"max_linear_x", xml_rpc_value))
170 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
173 if (!nh.getParam(
"max_linear_y", xml_rpc_value))
174 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
177 if (!nh.getParam(
"max_angular_z", xml_rpc_value))
178 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
182 nh.getParam(
"power_limit_topic", topic);
217 void set2DVel(
double scale_x,
double scale_y,
double scale_z)
249 XmlRpc::XmlRpcValue xml_rpc_value;
251 if (!nh.getParam(
"accel_x", xml_rpc_value))
252 ROS_ERROR(
"Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
254 accel_x_.
init(xml_rpc_value);
255 if (!nh.getParam(
"accel_y", xml_rpc_value))
256 ROS_ERROR(
"Accel Y no defined (namespace: %s)", nh.getNamespace().c_str());
258 accel_y_.
init(xml_rpc_value);
259 if (!nh.getParam(
"accel_z", xml_rpc_value))
260 ROS_ERROR(
"Accel Z no defined (namespace: %s)", nh.getNamespace().c_str());
262 accel_z_.
init(xml_rpc_value);
287 msg_.follow_vel_des = follow_vel_des;
291 msg_.wireless_state = state;
325 if (!nh.getParam(
"max_yaw_vel", max_yaw_vel_))
326 ROS_ERROR(
"Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
327 if (!nh.getParam(
"max_pitch_vel", max_pitch_vel_))
328 ROS_ERROR(
"Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
329 if (!nh.getParam(
"time_constant_rc", time_constant_rc_))
330 ROS_ERROR(
"Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
331 if (!nh.getParam(
"time_constant_pc", time_constant_pc_))
332 ROS_ERROR(
"Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
333 if (!nh.getParam(
"track_timeout", track_timeout_))
334 ROS_ERROR(
"Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
335 if (!nh.getParam(
"eject_sensitivity", eject_sensitivity_))
336 eject_sensitivity_ = 1.;
339 void setRate(
double scale_yaw,
double scale_pitch)
341 if (std::abs(scale_yaw) > 1)
342 scale_yaw = scale_yaw > 0 ? 1 : -1;
343 if (std::abs(scale_pitch) > 1)
344 scale_pitch = scale_pitch > 0 ? 1 : -1;
345 double time_constant{};
347 time_constant = time_constant_rc_;
349 time_constant = time_constant_pc_;
350 msg_.rate_yaw =
msg_.rate_yaw + (scale_yaw * max_yaw_vel_ -
msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
352 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ -
msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
355 msg_.rate_yaw *= eject_sensitivity_;
356 msg_.rate_pitch *= eject_sensitivity_;
361 msg_.traj_yaw = traj_yaw;
362 msg_.traj_pitch = traj_pitch;
371 msg_.rate_pitch = 0.;
375 msg_.bullet_speed = bullet_speed;
391 msg_.target_pos = point;
395 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
396 double time_constant_rc_{}, time_constant_pc_{};
397 bool eject_flag_{}, use_rc_{};
405 ros::NodeHandle limit_nh(nh,
"heat_limit");
407 nh.param(
"speed_10m_per_speed", speed_10_, 10.);
408 nh.param(
"speed_15m_per_speed", speed_15_, 15.);
409 nh.param(
"speed_16m_per_speed", speed_16_, 16.);
410 nh.param(
"speed_18m_per_speed", speed_18_, 18.);
411 nh.param(
"speed_30m_per_speed", speed_30_, 30.);
412 nh.getParam(
"wheel_speed_10", wheel_speed_10_);
413 nh.getParam(
"wheel_speed_15", wheel_speed_15_);
414 nh.getParam(
"wheel_speed_16", wheel_speed_16_);
415 nh.getParam(
"wheel_speed_18", wheel_speed_18_);
416 nh.getParam(
"wheel_speed_30", wheel_speed_30_);
417 nh.param(
"wheel_speed_offset_front", wheel_speed_offset_front_, 0.0);
418 nh.param(
"wheel_speed_offset_back", wheel_speed_offset_back_, 0.0);
419 nh.param(
"speed_oscillation", speed_oscillation_, 1.0);
420 nh.param(
"extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
421 nh.param(
"deploy_wheel_speed", deploy_wheel_speed_, 410.0);
422 if (!nh.getParam(
"auto_wheel_speed", auto_wheel_speed_))
423 ROS_INFO(
"auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
424 if (!nh.getParam(
"target_acceleration_tolerance", target_acceleration_tolerance_))
426 target_acceleration_tolerance_ = 0.;
427 ROS_INFO(
"target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
429 if (!nh.getParam(
"track_armor_error_tolerance", track_armor_error_tolerance_))
430 ROS_ERROR(
"track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
431 nh.param(
"untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
432 nh.param(
"track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
433 if (!nh.getParam(
"max_track_target_vel", max_track_target_vel_))
435 max_track_target_vel_ = 9.0;
436 ROS_ERROR(
"max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
458 gimbal_des_error_ = error;
462 shoot_beforehand_cmd_ = data;
470 suggest_fire_ = data;
475 if (auto_wheel_speed_)
477 if (last_bullet_speed_ == 0.0)
478 last_bullet_speed_ = speed_des_;
479 if (shoot_data_.bullet_speed != last_bullet_speed_)
481 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
483 total_extra_wheel_speed_ -= 5.0;
485 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
487 total_extra_wheel_speed_ += 5.0;
490 if (shoot_data_.bullet_speed != 0.0)
491 last_bullet_speed_ = shoot_data_.bullet_speed;
496 if (
msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
498 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
500 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
502 setMode(rm_msgs::ShootCmd::READY);
506 double gimbal_error_tolerance;
507 if (track_data_.id == 12)
508 gimbal_error_tolerance = track_buff_error_tolerance_;
509 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
510 gimbal_error_tolerance = track_armor_error_tolerance_;
512 gimbal_error_tolerance = untrack_armor_error_tolerance_;
513 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
514 (track_data_.accel > target_acceleration_tolerance_)) ||
515 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
516 if (
msg_.mode == rm_msgs::ShootCmd::PUSH)
518 setMode(rm_msgs::ShootCmd::READY);
540 return deploy_wheel_speed_;
541 return wheel_speed_des_;
543 return wheel_speed_des_ + total_extra_wheel_speed_;
561 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
564 speed_des_ = speed_10_;
565 wheel_speed_des_ = wheel_speed_10_;
568 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
571 speed_des_ = speed_15_;
572 wheel_speed_des_ = wheel_speed_15_;
575 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
578 speed_des_ = speed_16_;
579 wheel_speed_des_ = wheel_speed_16_;
582 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
585 speed_des_ = speed_18_;
586 wheel_speed_des_ = wheel_speed_18_;
589 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
592 speed_des_ = speed_30_;
593 wheel_speed_des_ = wheel_speed_30_;
600 wheels_speed_offset_front_ = wheel_speed_offset_front_;
601 return wheels_speed_offset_front_;
605 wheels_speed_offset_back_ = wheel_speed_offset_back_;
606 return wheels_speed_offset_back_;
611 wheel_speed_offset_front_ -= extra_wheel_speed_once_;
613 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
618 wheel_speed_offset_front_ += extra_wheel_speed_once_;
620 total_extra_wheel_speed_ += extra_wheel_speed_once_;
624 armor_type_ = armor_type;
643 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
644 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
645 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
646 double wheel_speed_offset_front_{}, wheel_speed_offset_back_{};
647 double wheels_speed_offset_front_{}, wheels_speed_offset_back_{};
648 double track_armor_error_tolerance_{};
649 double track_buff_error_tolerance_{};
650 double untrack_armor_error_tolerance_{};
651 double max_track_target_vel_{};
652 double target_acceleration_tolerance_{};
653 double extra_wheel_speed_once_{};
654 double total_extra_wheel_speed_{};
655 double deploy_wheel_speed_{};
656 bool auto_wheel_speed_ =
false;
658 bool deploy_flag_ =
false;
659 rm_msgs::TrackData track_data_;
660 rm_msgs::GimbalDesError gimbal_des_error_;
661 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
662 rm_msgs::ShootData shoot_data_;
663 std_msgs::Bool suggest_fire_;
664 uint8_t armor_type_{};
716 msg_.leg_length = length;
724 return msg_.leg_length;
734 if (!nh.getParam(
"max_linear_x", max_linear_x_))
735 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
736 if (!nh.getParam(
"max_linear_y", max_linear_y_))
737 ROS_ERROR(
"Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
738 if (!nh.getParam(
"max_linear_z", max_linear_z_))
739 ROS_ERROR(
"Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
740 if (!nh.getParam(
"max_angular_x", max_angular_x_))
741 ROS_ERROR(
"Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
742 if (!nh.getParam(
"max_angular_y", max_angular_y_))
743 ROS_ERROR(
"Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
744 if (!nh.getParam(
"max_angular_z", max_angular_z_))
745 ROS_ERROR(
"Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
749 msg_.twist.linear.x = max_linear_x_ * scale_x;
750 msg_.twist.linear.y = max_linear_y_ * scale_y;
751 msg_.twist.linear.z = max_linear_z_ * scale_z;
755 msg_.twist.angular.x = max_angular_x_ * scale_x;
756 msg_.twist.angular.y = max_angular_y_ * scale_y;
757 msg_.twist.angular.z = max_angular_z_ * scale_z;
761 msg_.twist.linear.x = 0.;
762 msg_.twist.linear.y = 0.;
763 msg_.twist.linear.z = 0.;
764 msg_.twist.angular.x = 0.;
765 msg_.twist.angular.y = 0.;
766 msg_.twist.angular.z = 0.;
770 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
778 ROS_ASSERT(nh.getParam(
"on_pos", on_pos_) && nh.getParam(
"off_pos", off_pos_));
787 msg_.data = off_pos_;
792 current_position_ =
msg_.data;
793 change_position_ = current_position_ + scale * per_change_position_;
794 msg_.data = change_position_;
808 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
816 ROS_ASSERT(nh.getParam(
"long_pos", long_pos_) && nh.getParam(
"short_pos", short_pos_) &&
817 nh.getParam(
"off_pos", off_pos_));
821 msg_.data = long_pos_;
826 msg_.data = short_pos_;
831 msg_.data = off_pos_;
846 double long_pos_{}, short_pos_{}, off_pos_{};
855 ROS_ASSERT(nh.getParam(
"joint", joint_));
856 ROS_ASSERT(nh.getParam(
"step", step_));
860 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
861 if (i != joint_state_.name.end())
862 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
868 if (
msg_.data != NAN)
876 if (
msg_.data != NAN)
888 std::string joint_{};
889 const sensor_msgs::JointState& joint_state_;
899 ROS_ASSERT(nh.getParam(
"joint", joint_));
907 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
908 if (i != joint_state_.name.end())
910 index_ = std::distance(joint_state_.name.begin(), i);
915 ROS_ERROR(
"Can not find joint %s", joint_.c_str());
922 std::string joint_{};
924 const sensor_msgs::JointState& joint_state_;
932 ROS_ASSERT(nh.getParam(
"camera_left_name", camera1_name_) && nh.getParam(
"camera_right_name", camera2_name_));
933 msg_.data = camera2_name_;
937 msg_.data = camera1_name_;
941 msg_.data = camera2_name_;
950 std::string camera1_name_{}, camera2_name_{};
968 void setGroupValue(
double linear_x,
double linear_y,
double linear_z,
double angular_x,
double angular_y,
971 msg_.linear.x = linear_x;
972 msg_.linear.y = linear_y;
973 msg_.linear.z = linear_z;
974 msg_.angular.x = angular_x;
975 msg_.angular.y = angular_y;
976 msg_.angular.z = angular_z;
997 ros::NodeHandle shooter_ID1_nh(nh,
"shooter_ID1");
999 ros::NodeHandle shooter_ID2_nh(nh,
"shooter_ID2");
1001 ros::NodeHandle barrel_nh(nh,
"barrel");
1004 barrel_nh.getParam(
"is_double_barrel", is_double_barrel_);
1005 barrel_nh.getParam(
"id1_point", id1_point_);
1006 barrel_nh.getParam(
"id2_point", id2_point_);
1007 barrel_nh.getParam(
"frequency_threshold", frequency_threshold_);
1008 barrel_nh.getParam(
"check_launch_threshold", check_launch_threshold_);
1009 barrel_nh.getParam(
"check_switch_threshold", check_switch_threshold_);
1010 barrel_nh.getParam(
"ready_duration", ready_duration_);
1011 barrel_nh.getParam(
"switching_duration", switching_duration_);
1013 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>(
"/joint_states", 10,
1014 &DoubleBarrelCommandSender::jointStateCallback,
this);
1015 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
1016 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback,
this);
1070 need_switch_ =
true;
1074 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1075 last_push_time_ = time;
1080 ros::Time time = ros::Time::now();
1081 barrel_command_sender_->
setPoint(id1_point_);
1082 shooter_ID1_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1083 shooter_ID2_cmd_sender_->
setMode(rm_msgs::ShootCmd::STOP);
1109 if (barrel_command_sender_->
getMsg()->data == id1_point_)
1113 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1117 ros::Time time = ros::Time::now();
1118 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1119 setMode(rm_msgs::ShootCmd::READY);
1120 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1122 barrel_command_sender_->
getMsg()->data == id2_point_ ? barrel_command_sender_->
setPoint(id1_point_) :
1123 barrel_command_sender_->
setPoint(id2_point_);
1125 last_switch_time_ = time;
1126 need_switch_ =
false;
1127 is_switching_ =
true;
1133 ros::Time time = ros::Time::now();
1136 setMode(rm_msgs::ShootCmd::READY);
1137 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1138 (std::abs(joint_state_.position[barrel_command_sender_->
getIndex()] -
1139 barrel_command_sender_->
getMsg()->data) < check_launch_threshold_))
1140 is_switching_ =
false;
1146 if (!is_double_barrel_)
1151 ROS_WARN_ONCE(
"Can not get cooling limit");
1157 if (getBarrel() == shooter_ID1_cmd_sender_)
1167 void triggerStateCallback(
const control_msgs::JointControllerState::ConstPtr& data)
1169 trigger_error_ = data->error;
1171 void jointStateCallback(
const sensor_msgs::JointState::ConstPtr& data)
1173 joint_state_ = *data;
1175 ShooterCommandSender* shooter_ID1_cmd_sender_;
1176 ShooterCommandSender* shooter_ID2_cmd_sender_;
1177 JointPointCommandSender* barrel_command_sender_{};
1178 ros::Subscriber trigger_state_sub_;
1179 ros::Subscriber joint_state_sub_;
1180 sensor_msgs::JointState joint_state_;
1181 bool is_double_barrel_{
false }, need_switch_{
false }, is_switching_{
false };
1182 ros::Time last_switch_time_, last_push_time_;
1183 double ready_duration_, switching_duration_;
1184 double trigger_error_;
1185 bool is_id1_{
false };
1186 double id1_point_, id2_point_;
1187 double frequency_threshold_;
1188 double check_launch_threshold_, check_switch_threshold_;
Definition command_sender.h:686
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:688
int getBalanceMode()
Definition command_sender.h:696
void setZero() override
Definition command_sender.h:700
void setBalanceMode(const int mode)
Definition command_sender.h:692
Definition command_sender.h:928
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:930
void setZero() override
Definition command_sender.h:947
void switchCameraRight()
Definition command_sender.h:939
void switchCameraLeft()
Definition command_sender.h:935
void sendCommand(const ros::Time &time) override
Definition command_sender.h:943
Definition command_sender.h:812
void long_on()
Definition command_sender.h:819
void off()
Definition command_sender.h:829
void sendCommand(const ros::Time &time) override
Definition command_sender.h:838
void setZero() override
Definition command_sender.h:842
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:814
bool getState() const
Definition command_sender.h:834
void short_on()
Definition command_sender.h:824
Definition command_sender.h:309
void setZero() override
Definition command_sender.h:315
ChassisActiveSuspensionCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:311
Definition command_sender.h:245
void setFollowVelDes(double follow_vel_des)
Definition command_sender.h:285
void updateRefereeStatus(bool status)
Definition command_sender.h:281
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:269
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition command_sender.h:293
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition command_sender.h:277
ChassisCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:247
PowerLimit * power_limit_
Definition command_sender.h:302
void setZero() override
Definition command_sender.h:301
void setWirelessState(bool state)
Definition command_sender.h:289
void updateSafetyPower(int safety_power)
Definition command_sender.h:265
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:273
Definition command_sender.h:92
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:110
virtual void sendCommand(const ros::Time &time)
Definition command_sender.h:106
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:119
void setMode(int mode)
Definition command_sender.h:101
ros::Publisher pub_
Definition command_sender.h:131
uint32_t queue_size_
Definition command_sender.h:130
MsgType msg_
Definition command_sender.h:132
MsgType * getMsg()
Definition command_sender.h:123
CommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:94
std::string topic_
Definition command_sender.h:129
virtual void updateGameStatus(const rm_msgs::GameStatus data)
Definition command_sender.h:113
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition command_sender.h:116
Definition command_sender.h:993
void setZero()
Definition command_sender.h:1059
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:995
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:1039
double getSpeed()
Definition command_sender.h:1101
void setMode(int mode)
Definition command_sender.h:1055
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:1044
void sendCommand(const ros::Time &time)
Definition command_sender.h:1067
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:1034
void init()
Definition command_sender.h:1078
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:1049
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:1019
void updateRefereeStatus(bool status)
Definition command_sender.h:1029
void setShootFrequency(uint8_t mode)
Definition command_sender.h:1093
void setArmorType(uint8_t armor_type)
Definition command_sender.h:1088
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:1024
uint8_t getShootFrequency()
Definition command_sender.h:1097
void checkError(const ros::Time &time)
Definition command_sender.h:1063
Definition command_sender.h:321
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:339
~GimbalCommandSender()=default
bool getEject() const
Definition command_sender.h:385
void setUseRc(bool flag)
Definition command_sender.h:381
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:373
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:389
void setTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:364
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:359
void setEject(bool flag)
Definition command_sender.h:377
void setZero() override
Definition command_sender.h:368
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:323
Definition command_sender.h:151
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:153
void sendCommand(const ros::Time &time) override
Definition command_sender.h:156
Definition heat_limit.h:52
int getCoolingLimit()
Definition heat_limit.h:178
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:188
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:166
bool getShootFrequencyMode() const
Definition heat_limit.h:193
Definition command_sender.h:850
void reset()
Definition command_sender.h:858
const std::string & getJoint()
Definition command_sender.h:882
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:852
void minus()
Definition command_sender.h:874
void plus()
Definition command_sender.h:866
Definition command_sender.h:894
int getIndex()
Definition command_sender.h:905
void setZero() override
Definition command_sender.h:919
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:896
void setPoint(double point)
Definition command_sender.h:901
Definition command_sender.h:774
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:776
void sendCommand(const ros::Time &time) override
Definition command_sender.h:800
void setZero() override
Definition command_sender.h:804
bool getState() const
Definition command_sender.h:796
void changePosition(double scale)
Definition command_sender.h:790
void off()
Definition command_sender.h:785
void on()
Definition command_sender.h:780
Definition command_sender.h:704
void setZero() override
Definition command_sender.h:726
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:706
void setLgeLength(double length)
Definition command_sender.h:714
bool getJump()
Definition command_sender.h:718
double getLgeLength()
Definition command_sender.h:722
void setJump(bool jump)
Definition command_sender.h:710
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:954
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:968
~MultiDofCommandSender()=default
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:956
int getMode()
Definition command_sender.h:964
void setZero() override
Definition command_sender.h:978
void setMode(int mode)
Definition command_sender.h:960
Definition power_limit.h:53
void setRefereeStatus(bool status)
Definition power_limit.h:131
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:125
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:120
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:115
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:176
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition command_sender.h:401
void setShootFrequency(uint8_t mode)
Definition command_sender.h:626
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:468
void setZero() override
Definition command_sender.h:634
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:448
void sendCommand(const ros::Time &time) override
Definition command_sender.h:521
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:464
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:557
uint8_t getShootFrequency()
Definition command_sender.h:630
void setDeployState(bool flag)
Definition command_sender.h:545
void setHeroState(bool flag)
Definition command_sender.h:549
void dropSpeed()
Definition command_sender.h:608
int getShootMode()
Definition command_sender.h:637
double getBackWheelSpeedOffset()
Definition command_sender.h:603
void updateRefereeStatus(bool status)
Definition command_sender.h:452
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:403
double getFrontWheelSpeedOffset()
Definition command_sender.h:598
double getWheelSpeedDes()
Definition command_sender.h:534
~ShooterCommandSender()
Definition command_sender.h:439
void raiseSpeed()
Definition command_sender.h:615
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:444
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:472
void setArmorType(uint8_t armor_type)
Definition command_sender.h:622
double getSpeed()
Definition command_sender.h:529
void checkError(const ros::Time &time)
Definition command_sender.h:494
HeatLimit * heat_limit_
Definition command_sender.h:635
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:456
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:460
bool getDeployState()
Definition command_sender.h:553
Definition command_sender.h:137
void sendCommand(const ros::Time &time) override
Definition command_sender.h:142
TimeStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:139
Definition command_sender.h:668
void setUseLio(bool flag)
Definition command_sender.h:674
void setZero() override
Definition command_sender.h:682
bool getUseLio() const
Definition command_sender.h:678
UseLioCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:670
Definition command_sender.h:164
ros::Subscriber chassis_power_limit_subscriber_
Definition command_sender.h:240
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:188
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
Definition command_sender.h:231
void setAngularZVel(double scale, double limit)
Definition command_sender.h:208
void setLinearYVel(double scale)
Definition command_sender.h:196
void setAngularZVel(double scale)
Definition command_sender.h:200
void setLinearXVel(double scale)
Definition command_sender.h:192
void set2DVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:217
double target_vel_yaw_threshold_
Definition command_sender.h:238
rm_msgs::TrackData track_data_
Definition command_sender.h:241
LinearInterp max_linear_x_
Definition command_sender.h:236
LinearInterp max_linear_y_
Definition command_sender.h:236
double vel_direction_
Definition command_sender.h:239
LinearInterp max_angular_z_
Definition command_sender.h:236
double power_limit_
Definition command_sender.h:237
void setZero() override
Definition command_sender.h:223
Vel2DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:166
Definition command_sender.h:730
void setZero() override
Definition command_sender.h:759
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:732
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:753
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:747
auto setTrajFrameIdIfSupported(TMsg &msg, const std::string &traj_frame_id, int) -> decltype((void)(msg.traj_frame_id=traj_frame_id), void())
Definition command_sender.h:78
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string ¶m_name, const T &default_val)
Definition ros_utilities.h:44