command_sender.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 5/18/21.
36 //
37 
38 #pragma once
39 
40 #include <type_traits>
41 #include <utility>
42 
43 #include <ros/ros.h>
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>
64 
70 
71 namespace rm_common
72 {
73 template <class MsgType>
74 class CommandSenderBase
75 {
76 public:
78  {
79  if (!nh.getParam("topic", topic_))
80  ROS_ERROR("Topic name no defined (namespace: %s)", nh.getNamespace().c_str());
81  queue_size_ = getParam(nh, "queue_size", 1);
82  pub_ = nh.advertise<MsgType>(topic_, queue_size_);
83  }
84  void setMode(int mode)
85  {
86  if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
87  msg_.mode = mode;
88  }
89  virtual void sendCommand(const ros::Time& time)
90  {
91  pub_.publish(msg_);
92  }
93  virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
94  {
95  }
96  virtual void updateGameStatus(const rm_msgs::GameStatus data)
97  {
98  }
99  virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
100  {
101  }
102  virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
103  {
104  }
105  virtual void setZero() = 0;
106  MsgType* getMsg()
107  {
108  return &msg_;
109  }
110 
111 protected:
112  std::string topic_;
113  uint32_t queue_size_;
115  MsgType msg_;
116 };
117 
118 template <class MsgType>
119 class TimeStampCommandSenderBase : public CommandSenderBase<MsgType>
120 {
121 public:
123  {
124  }
125  void sendCommand(const ros::Time& time) override
126  {
129  }
130 };
131 
132 template <class MsgType>
133 class HeaderStampCommandSenderBase : public CommandSenderBase<MsgType>
134 {
135 public:
137  {
138  }
139  void sendCommand(const ros::Time& time) override
140  {
141  CommandSenderBase<MsgType>::msg_.header.stamp = time;
143  }
144 };
145 
146 class Vel2DCommandSender : public CommandSenderBase<geometry_msgs::Twist>
147 {
148 public:
150  {
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());
154  else
155  max_linear_x_.init(xml_rpc_value);
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());
158  else
159  max_linear_y_.init(xml_rpc_value);
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());
162  else
163  max_angular_z_.init(xml_rpc_value);
164  std::string topic;
165  nh.getParam("power_limit_topic", topic);
166  target_vel_yaw_threshold_ = getParam(nh, "target_vel_yaw_threshold", 3.);
168  nh.subscribe<rm_msgs::ChassisCmd>(topic, 1, &Vel2DCommandSender::chassisCmdCallback, this);
169  }
170 
171  void updateTrackData(const rm_msgs::TrackData& data)
172  {
173  track_data_ = data;
174  }
175  void setLinearXVel(double scale)
176  {
177  msg_.linear.x = scale * max_linear_x_.output(power_limit_);
178  };
179  void setLinearYVel(double scale)
180  {
181  msg_.linear.y = scale * max_linear_y_.output(power_limit_);
182  };
183  void setAngularZVel(double scale)
184  {
186  vel_direction_ = -1.;
188  vel_direction_ = 1.;
189  msg_.angular.z = scale * max_angular_z_.output(power_limit_) * vel_direction_;
190  };
191  void setAngularZVel(double scale, double limit)
192  {
194  vel_direction_ = -1.;
196  vel_direction_ = 1.;
197  double angular_z = max_angular_z_.output(power_limit_) > limit ? limit : max_angular_z_.output(power_limit_);
198  msg_.angular.z = scale * angular_z * vel_direction_;
199  };
200  void set2DVel(double scale_x, double scale_y, double scale_z)
201  {
202  setLinearXVel(scale_x);
203  setLinearYVel(scale_y);
204  setAngularZVel(scale_z);
205  }
206  void setZero() override
207  {
208  msg_.linear.x = 0.;
209  msg_.linear.y = 0.;
210  msg_.angular.z = 0.;
211  }
212 
213 protected:
214  void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr& msg)
215  {
216  power_limit_ = msg->power_limit;
217  }
218 
220  double power_limit_ = 0.;
221  double target_vel_yaw_threshold_{};
222  double vel_direction_ = 1.;
224  rm_msgs::TrackData track_data_;
225 };
226 
227 class ChassisCommandSender : public TimeStampCommandSenderBase<rm_msgs::ChassisCmd>
228 {
229 public:
231  {
232  XmlRpc::XmlRpcValue xml_rpc_value;
233  power_limit_ = new PowerLimit(nh);
234  if (!nh.getParam("accel_x", xml_rpc_value))
235  ROS_ERROR("Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
236  else
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());
240  else
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());
244  else
245  accel_z_.init(xml_rpc_value);
246  }
247 
248  void updateSafetyPower(int safety_power)
249  {
251  }
252  void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
253  {
255  }
256  void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
257  {
259  }
260  void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
261  {
263  }
264  void updateRefereeStatus(bool status)
265  {
267  }
268  void setFollowVelDes(double follow_vel_des)
269  {
270  msg_.follow_vel_des = follow_vel_des;
271  }
272  void sendChassisCommand(const ros::Time& time, bool is_gyro)
273  {
274  power_limit_->setLimitPower(msg_, is_gyro);
275  msg_.accel.linear.x = accel_x_.output(msg_.power_limit);
276  msg_.accel.linear.y = accel_y_.output(msg_.power_limit);
277  msg_.accel.angular.z = accel_z_.output(msg_.power_limit);
279  }
280  void setZero() override{};
281  PowerLimit* power_limit_;
282 
283 private:
285 };
286 
287 class GimbalCommandSender : public TimeStampCommandSenderBase<rm_msgs::GimbalCmd>
288 {
289 public:
291  {
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_))
304  }
305  ~GimbalCommandSender() = default;
306  void setRate(double scale_yaw, double scale_pitch)
307  {
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{};
313  if (use_rc_)
314  time_constant = time_constant_rc_;
315  else
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));
318  msg_.rate_pitch =
319  msg_.rate_pitch + (scale_pitch * max_pitch_vel_ - msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
320  if (eject_flag_)
321  {
322  msg_.rate_yaw *= eject_sensitivity_;
323  msg_.rate_pitch *= eject_sensitivity_;
324  }
325  }
326  void setGimbalTraj(double traj_yaw, double traj_pitch)
327  {
328  msg_.traj_yaw = traj_yaw;
329  msg_.traj_pitch = traj_pitch;
330  }
331  void setZero() override
332  {
333  msg_.rate_yaw = 0.;
334  msg_.rate_pitch = 0.;
335  }
336  void setBulletSpeed(double bullet_speed)
337  {
338  msg_.bullet_speed = bullet_speed;
339  }
340  void setEject(bool flag)
341  {
342  eject_flag_ = flag;
343  }
344  void setUseRc(bool flag)
345  {
346  use_rc_ = flag;
347  }
348  bool getEject() const
349  {
350  return eject_flag_;
351  }
352  void setPoint(geometry_msgs::PointStamped point)
353  {
354  msg_.target_pos = point;
355  }
356 
357 private:
360  bool eject_flag_{}, use_rc_{};
361 };
362 
363 class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd>
364 {
365 public:
367  {
368  ros::NodeHandle limit_nh(nh, "heat_limit");
369  heat_limit_ = new HeatLimit(limit_nh);
370  nh.param("speed_10m_per_speed", speed_10_, 10.);
371  nh.param("speed_15m_per_speed", speed_15_, 15.);
372  nh.param("speed_16m_per_speed", speed_16_, 16.);
373  nh.param("speed_18m_per_speed", speed_18_, 18.);
374  nh.param("speed_30m_per_speed", speed_30_, 30.);
375  nh.getParam("wheel_speed_10", wheel_speed_10_);
376  nh.getParam("wheel_speed_15", wheel_speed_15_);
377  nh.getParam("wheel_speed_16", wheel_speed_16_);
378  nh.getParam("wheel_speed_18", wheel_speed_18_);
379  nh.getParam("wheel_speed_30", wheel_speed_30_);
380  nh.param("speed_oscillation", speed_oscillation_, 1.0);
381  nh.param("extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
382  if (!nh.getParam("auto_wheel_speed", auto_wheel_speed_))
383  ROS_INFO("auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
384  if (!nh.getParam("target_acceleration_tolerance", target_acceleration_tolerance_))
385  {
387  ROS_INFO("target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
388  }
389  if (!nh.getParam("track_armor_error_tolerance", track_armor_error_tolerance_))
390  ROS_ERROR("track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
392  nh.param("track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
393  if (!nh.getParam("max_track_target_vel", max_track_target_vel_))
394  {
395  max_track_target_vel_ = 9.0;
396  ROS_ERROR("max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
397  }
398  }
400  {
401  delete heat_limit_;
402  }
403 
404  void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
405  {
407  }
408  void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
409  {
411  }
412  void updateRefereeStatus(bool status)
413  {
414  heat_limit_->setRefereeStatus(status);
415  }
416  void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
417  {
418  gimbal_des_error_ = error;
419  }
420  void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
421  {
422  shoot_beforehand_cmd_ = data;
423  }
424  void updateTrackData(const rm_msgs::TrackData& data)
425  {
426  track_data_ = data;
427  }
428  void updateSuggestFireData(const std_msgs::Bool& data)
429  {
431  }
432  void updateShootData(const rm_msgs::ShootData& data)
433  {
434  shoot_data_ = data;
436  {
437  if (last_bullet_speed_ == 0.0)
439  if (shoot_data_.bullet_speed != last_bullet_speed_)
440  {
442  {
444  }
446  {
448  }
449  }
450  if (shoot_data_.bullet_speed != 0.0)
452  }
453  }
454  void checkError(const ros::Time& time)
455  {
456  if (msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
457  {
458  if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
459  return;
460  if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
461  {
462  setMode(rm_msgs::ShootCmd::READY);
463  return;
464  }
465  }
466  double gimbal_error_tolerance;
467  if (track_data_.id == 12)
468  gimbal_error_tolerance = track_buff_error_tolerance_;
469  else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
470  gimbal_error_tolerance = track_armor_error_tolerance_;
471  else
472  gimbal_error_tolerance = untrack_armor_error_tolerance_;
473  if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
475  (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
476  if (msg_.mode == rm_msgs::ShootCmd::PUSH)
477  setMode(rm_msgs::ShootCmd::READY);
478  }
479  void sendCommand(const ros::Time& time) override
480  {
481  msg_.wheel_speed = getWheelSpeedDes();
484  }
485  double getSpeed()
486  {
488  return speed_des_;
489  }
490  double getWheelSpeedDes()
491  {
494  }
496  {
497  switch (heat_limit_->getSpeedLimit())
498  {
499  case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
500  {
501  speed_limit_ = 10.0;
504  break;
505  }
506  case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
507  {
508  speed_limit_ = 15.0;
511  break;
512  }
513  case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
514  {
515  speed_limit_ = 16.0;
518  break;
519  }
520  case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
521  {
522  speed_limit_ = 18.0;
525  break;
526  }
527  case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
528  {
529  speed_limit_ = 30.0;
532  break;
533  }
534  }
535  }
536  void dropSpeed()
537  {
539  }
540  void raiseSpeed()
541  {
543  }
544  void setArmorType(uint8_t armor_type)
545  {
546  armor_type_ = armor_type;
547  }
548  void setShootFrequency(uint8_t mode)
549  {
551  }
552  uint8_t getShootFrequency()
553  {
555  }
556  void setZero() override{};
557  HeatLimit* heat_limit_{};
558 
559 private:
566  double max_track_target_vel_{};
568  double extra_wheel_speed_once_{};
569  double total_extra_wheel_speed_{};
570  bool auto_wheel_speed_ = false;
571  rm_msgs::TrackData track_data_;
572  rm_msgs::GimbalDesError gimbal_des_error_;
573  rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
574  rm_msgs::ShootData shoot_data_;
575  std_msgs::Bool suggest_fire_;
576  uint8_t armor_type_{};
577 };
578 
579 class BalanceCommandSender : public CommandSenderBase<std_msgs::UInt8>
580 {
581 public:
583  {
584  }
585 
586  void setBalanceMode(const int mode)
587  {
588  msg_.data = mode;
589  }
590  int getBalanceMode()
591  {
592  return msg_.data;
593  }
594  void setZero() override{};
595 };
596 
597 class LegCommandSender : public CommandSenderBase<rm_msgs::LegCmd>
598 {
599 public:
600  explicit LegCommandSender(ros::NodeHandle& nh) : CommandSenderBase<rm_msgs::LegCmd>(nh)
601  {
602  }
603 
604  void setJump(bool jump)
605  {
606  msg_.jump = jump;
607  }
608  void setLgeLength(double length)
609  {
610  msg_.leg_length = length;
611  }
612  bool getJump()
613  {
614  return msg_.jump;
615  }
616  double getLgeLength()
617  {
618  return msg_.leg_length;
619  }
620  void setZero() override{};
621 };
622 
623 class Vel3DCommandSender : public HeaderStampCommandSenderBase<geometry_msgs::TwistStamped>
624 {
625 public:
627  {
628  if (!nh.getParam("max_linear_x", max_linear_x_))
629  ROS_ERROR("Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
630  if (!nh.getParam("max_linear_y", max_linear_y_))
631  ROS_ERROR("Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
632  if (!nh.getParam("max_linear_z", max_linear_z_))
633  ROS_ERROR("Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
634  if (!nh.getParam("max_angular_x", max_angular_x_))
635  ROS_ERROR("Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
636  if (!nh.getParam("max_angular_y", max_angular_y_))
637  ROS_ERROR("Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
638  if (!nh.getParam("max_angular_z", max_angular_z_))
639  ROS_ERROR("Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
640  }
641  void setLinearVel(double scale_x, double scale_y, double scale_z)
642  {
643  msg_.twist.linear.x = max_linear_x_ * scale_x;
644  msg_.twist.linear.y = max_linear_y_ * scale_y;
645  msg_.twist.linear.z = max_linear_z_ * scale_z;
646  }
647  void setAngularVel(double scale_x, double scale_y, double scale_z)
648  {
649  msg_.twist.angular.x = max_angular_x_ * scale_x;
650  msg_.twist.angular.y = max_angular_y_ * scale_y;
651  msg_.twist.angular.z = max_angular_z_ * scale_z;
652  }
653  void setZero() override
654  {
655  msg_.twist.linear.x = 0.;
656  msg_.twist.linear.y = 0.;
657  msg_.twist.linear.z = 0.;
658  msg_.twist.angular.x = 0.;
659  msg_.twist.angular.y = 0.;
660  msg_.twist.angular.z = 0.;
661  }
662 
663 private:
665 };
666 
667 class JointPositionBinaryCommandSender : public CommandSenderBase<std_msgs::Float64>
668 {
669 public:
671  {
672  ROS_ASSERT(nh.getParam("on_pos", on_pos_) && nh.getParam("off_pos", off_pos_));
673  }
674  void on()
675  {
676  msg_.data = on_pos_;
677  state = true;
678  }
679  void off()
680  {
681  msg_.data = off_pos_;
682  state = false;
683  }
684  void changePosition(double scale)
685  {
686  current_position_ = msg_.data;
688  msg_.data = change_position_;
689  }
690  bool getState() const
691  {
692  return state;
693  }
694  void sendCommand(const ros::Time& time) override
695  {
697  }
698  void setZero() override{};
699 
700 private:
701  bool state{};
703 };
704 
705 class CardCommandSender : public CommandSenderBase<std_msgs::Float64>
706 {
707 public:
709  {
710  ROS_ASSERT(nh.getParam("long_pos", long_pos_) && nh.getParam("short_pos", short_pos_) &&
711  nh.getParam("off_pos", off_pos_));
712  }
713  void long_on()
714  {
715  msg_.data = long_pos_;
716  state = true;
717  }
718  void short_on()
719  {
720  msg_.data = short_pos_;
721  state = true;
722  }
723  void off()
724  {
725  msg_.data = off_pos_;
726  state = false;
727  }
728  bool getState() const
729  {
730  return state;
731  }
732  void sendCommand(const ros::Time& time) override
733  {
735  }
736  void setZero() override{};
737 
738 private:
739  bool state{};
740  double long_pos_{}, short_pos_{}, off_pos_{};
741 };
742 
743 class JointJogCommandSender : public CommandSenderBase<std_msgs::Float64>
744 {
745 public:
746  explicit JointJogCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
748  {
749  ROS_ASSERT(nh.getParam("joint", joint_));
750  ROS_ASSERT(nh.getParam("step", step_));
751  }
752  void reset()
753  {
754  auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
755  if (i != joint_state_.name.end())
756  msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
757  else
758  msg_.data = NAN;
759  }
760  void plus()
761  {
762  if (msg_.data != NAN)
763  {
764  msg_.data += step_;
766  }
767  }
768  void minus()
769  {
770  if (msg_.data != NAN)
771  {
772  msg_.data -= step_;
774  }
775  }
776  const std::string& getJoint()
777  {
778  return joint_;
779  }
780 
781 private:
782  std::string joint_{};
783  const sensor_msgs::JointState& joint_state_;
784  double step_{};
785 };
786 
787 class JointPointCommandSender : public CommandSenderBase<std_msgs::Float64>
788 {
789 public:
790  explicit JointPointCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
791  : CommandSenderBase<std_msgs::Float64>(nh), joint_state_(joint_state)
792  {
793  ROS_ASSERT(nh.getParam("joint", joint_));
794  }
795  void setPoint(double point)
796  {
797  msg_.data = point;
798  }
799  int getIndex()
800  {
801  auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
802  if (i != joint_state_.name.end())
803  {
804  index_ = std::distance(joint_state_.name.begin(), i);
805  return index_;
806  }
807  else
808  {
809  ROS_ERROR("Can not find joint %s", joint_.c_str());
810  return -1;
811  }
812  }
813  void setZero() override{};
814 
815 private:
816  std::string joint_{};
817  int index_{};
818  const sensor_msgs::JointState& joint_state_;
819 };
820 
821 class CameraSwitchCommandSender : public CommandSenderBase<std_msgs::String>
822 {
823 public:
825  {
826  ROS_ASSERT(nh.getParam("camera1_name", camera1_name_) && nh.getParam("camera2_name", camera2_name_));
827  msg_.data = camera1_name_;
828  }
829  void switchCamera()
830  {
832  }
833  void sendCommand(const ros::Time& time) override
834  {
836  }
837  void setZero() override{};
838 
839 private:
840  std::string camera1_name_{}, camera2_name_{};
841 };
842 
843 class MultiDofCommandSender : public TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>
844 {
845 public:
847  {
848  }
850  void setMode(int mode)
851  {
852  msg_.mode = mode;
853  }
854  int getMode()
855  {
856  return msg_.mode;
857  }
858  void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y,
859  double angular_z)
860  {
861  msg_.linear.x = linear_x;
862  msg_.linear.y = linear_y;
863  msg_.linear.z = linear_z;
864  msg_.angular.x = angular_x;
865  msg_.angular.y = angular_y;
866  msg_.angular.z = angular_z;
867  }
868  void setZero() override
869  {
870  msg_.linear.x = 0;
871  msg_.linear.y = 0;
872  msg_.linear.z = 0;
873  msg_.angular.x = 0;
874  msg_.angular.y = 0;
875  msg_.angular.z = 0;
876  }
877 
878 private:
880 };
881 
883 {
884 public:
886  {
887  ros::NodeHandle shooter_ID1_nh(nh, "shooter_ID1");
888  shooter_ID1_cmd_sender_ = new ShooterCommandSender(shooter_ID1_nh);
889  ros::NodeHandle shooter_ID2_nh(nh, "shooter_ID2");
890  shooter_ID2_cmd_sender_ = new ShooterCommandSender(shooter_ID2_nh);
891  ros::NodeHandle barrel_nh(nh, "barrel");
893 
894  barrel_nh.getParam("is_double_barrel", is_double_barrel_);
895  barrel_nh.getParam("id1_point", id1_point_);
896  barrel_nh.getParam("id2_point", id2_point_);
897  barrel_nh.getParam("frequency_threshold", frequency_threshold_);
898  barrel_nh.getParam("check_launch_threshold", check_launch_threshold_);
899  barrel_nh.getParam("check_switch_threshold", check_switch_threshold_);
900  barrel_nh.getParam("ready_duration", ready_duration_);
901  barrel_nh.getParam("switching_duration", switching_duration_);
902 
903  joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>("/joint_states", 10,
905  trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
906  "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback, this);
907  }
908 
909  void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
910  {
913  }
914  void updatePowerHeatData(const rm_msgs::PowerHeatData data)
915  {
918  }
919  void updateRefereeStatus(bool status)
920  {
923  }
924  void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
925  {
928  }
929  void updateTrackData(const rm_msgs::TrackData& data)
930  {
933  }
934  void updateSuggestFireData(const std_msgs::Bool& data)
935  {
938  }
939  void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
940  {
943  }
944 
945  void setMode(int mode)
946  {
947  getBarrel()->setMode(mode);
948  }
949  void setZero()
950  {
951  getBarrel()->setZero();
952  }
953  void checkError(const ros::Time& time)
954  {
956  }
957  void sendCommand(const ros::Time& time)
958  {
959  if (checkSwitch())
960  need_switch_ = true;
961  if (need_switch_)
962  switchBarrel();
963  checklaunch();
964  if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
966  getBarrel()->sendCommand(time);
967  }
968  void init()
969  {
972  shooter_ID1_cmd_sender_->setMode(rm_msgs::ShootCmd::STOP);
973  shooter_ID2_cmd_sender_->setMode(rm_msgs::ShootCmd::STOP);
977  }
978  void setArmorType(uint8_t armor_type)
979  {
982  }
983  void setShootFrequency(uint8_t mode)
984  {
985  getBarrel()->setShootFrequency(mode);
986  }
987  uint8_t getShootFrequency()
988  {
989  return getBarrel()->getShootFrequency();
990  }
991  double getSpeed()
992  {
993  return getBarrel()->getSpeed();
994  }
995 
996 private:
997  ShooterCommandSender* getBarrel()
998  {
1000  is_id1_ = true;
1001  else
1002  is_id1_ = false;
1004  }
1005  void switchBarrel()
1006  {
1007  ros::Time time = ros::Time::now();
1008  bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1009  setMode(rm_msgs::ShootCmd::READY);
1010  if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1011  {
1015  last_switch_time_ = time;
1016  need_switch_ = false;
1017  is_switching_ = true;
1018  }
1019  }
1020 
1021  void checklaunch()
1022  {
1023  ros::Time time = ros::Time::now();
1024  if (is_switching_)
1025  {
1026  setMode(rm_msgs::ShootCmd::READY);
1027  if ((time - last_switch_time_).toSec() > switching_duration_ ||
1030  is_switching_ = false;
1031  }
1032  }
1033 
1034  bool checkSwitch()
1035  {
1037  return false;
1040  {
1041  ROS_WARN_ONCE("Can not get cooling limit");
1042  return false;
1043  }
1046  {
1050  else
1053  }
1054  else
1055  return false;
1056  }
1057  void triggerStateCallback(const control_msgs::JointControllerState::ConstPtr& data)
1058  {
1059  trigger_error_ = data->error;
1060  }
1061  void jointStateCallback(const sensor_msgs::JointState::ConstPtr& data)
1062  {
1063  joint_state_ = *data;
1064  }
1070  sensor_msgs::JointState joint_state_;
1071  bool is_double_barrel_{ false }, need_switch_{ false }, is_switching_{ false };
1074  double trigger_error_;
1075  bool is_id1_{ false };
1076  double id1_point_, id2_point_;
1077  double frequency_threshold_;
1079 };
1080 
1081 } // namespace rm_common
rm_common::CardCommandSender::short_pos_
double short_pos_
Definition: command_sender.h:771
rm_common::CommandSenderBase::CommandSenderBase
CommandSenderBase(ros::NodeHandle &nh)
Definition: command_sender.h:139
rm_common::MultiDofCommandSender::getMode
int getMode()
Definition: command_sender.h:885
rm_common::HeatLimit
Definition: heat_limit.h:80
rm_common::GimbalCommandSender::max_pitch_vel_
double max_pitch_vel_
Definition: command_sender.h:389
rm_common::MultiDofCommandSender::setMode
void setMode(int mode)
Definition: command_sender.h:881
rm_common::ShooterCommandSender::updateGameRobotStatus
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition: command_sender.h:435
rm_common::DoubleBarrelCommandSender::getBarrel
ShooterCommandSender * getBarrel()
Definition: command_sender.h:1028
rm_common::Vel2DCommandSender::power_limit_
double power_limit_
Definition: command_sender.h:251
rm_common::BalanceCommandSender::getBalanceMode
int getBalanceMode()
Definition: command_sender.h:621
rm_common::CardCommandSender::setZero
void setZero() override
Definition: command_sender.h:767
rm_common::DoubleBarrelCommandSender::getShootFrequency
uint8_t getShootFrequency()
Definition: command_sender.h:1018
rm_common::MultiDofCommandSender::setGroupValue
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition: command_sender.h:889
rm_common::ShooterCommandSender
Definition: command_sender.h:394
ros::Publisher
rm_common::JointPositionBinaryCommandSender::off_pos_
double off_pos_
Definition: command_sender.h:733
rm_common::Vel2DCommandSender::max_linear_x_
LinearInterp max_linear_x_
Definition: command_sender.h:250
rm_common::DoubleBarrelCommandSender::setZero
void setZero()
Definition: command_sender.h:980
rm_common::HeatLimit::getSpeedLimit
int getSpeedLimit()
Definition: heat_limit.h:212
rm_common::ChassisCommandSender::accel_x_
LinearInterp accel_x_
Definition: command_sender.h:315
rm_common::ShooterCommandSender::updateGimbalDesError
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition: command_sender.h:447
rm_common::JointJogCommandSender::getJoint
const std::string & getJoint()
Definition: command_sender.h:807
rm_common::Vel2DCommandSender::max_linear_y_
LinearInterp max_linear_y_
Definition: command_sender.h:250
rm_common::CommandSenderBase::topic_
std::string topic_
Definition: command_sender.h:174
rm_common::ShooterCommandSender::wheel_speed_15_
double wheel_speed_15_
Definition: command_sender.h:592
rm_common::JointJogCommandSender::plus
void plus()
Definition: command_sender.h:791
rm_common::ShooterCommandSender::track_data_
rm_msgs::TrackData track_data_
Definition: command_sender.h:602
rm_common::ChassisCommandSender
Definition: command_sender.h:258
rm_common::LinearInterp
Definition: linear_interpolation.h:11
rm_common::LegCommandSender
Definition: command_sender.h:628
rm_common::LegCommandSender::getJump
bool getJump()
Definition: command_sender.h:643
rm_common::DoubleBarrelCommandSender::setShootFrequency
void setShootFrequency(uint8_t mode)
Definition: command_sender.h:1014
rm_common::Vel2DCommandSender::chassisCmdCallback
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
Definition: command_sender.h:245
rm_common::HeatLimit::getCoolingLimit
int getCoolingLimit()
Definition: heat_limit.h:224
rm_common::Vel2DCommandSender::chassis_power_limit_subscriber_
ros::Subscriber chassis_power_limit_subscriber_
Definition: command_sender.h:254
rm_common::LegCommandSender::setJump
void setJump(bool jump)
Definition: command_sender.h:635
rm_common::Vel3DCommandSender::setZero
void setZero() override
Definition: command_sender.h:684
rm_common::GimbalCommandSender::getEject
bool getEject() const
Definition: command_sender.h:379
rm_common::ShooterCommandSender::speed_15_
double speed_15_
Definition: command_sender.h:591
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
rm_common::CardCommandSender::getState
bool getState() const
Definition: command_sender.h:759
ros.h
rm_common::ShooterCommandSender::armor_type_
uint8_t armor_type_
Definition: command_sender.h:607
rm_common::DoubleBarrelCommandSender::check_switch_threshold_
double check_switch_threshold_
Definition: command_sender.h:1109
rm_common::Vel3DCommandSender::Vel3DCommandSender
Vel3DCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:657
rm_common::LinearInterp::output
double output(double input)
Definition: linear_interpolation.h:37
rm_common::JointPositionBinaryCommandSender::off
void off()
Definition: command_sender.h:710
rm_common::ChassisCommandSender::updateSafetyPower
void updateSafetyPower(int safety_power)
Definition: command_sender.h:279
rm_common::ShooterCommandSender::track_armor_error_tolerance_
double track_armor_error_tolerance_
Definition: command_sender.h:594
rm_common::ShooterCommandSender::setZero
void setZero() override
Definition: command_sender.h:587
rm_common::CameraSwitchCommandSender::CameraSwitchCommandSender
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:855
heat_limit.h
rm_common::CommandSenderBase
Definition: command_sender.h:105
rm_common::ShooterCommandSender::updateRefereeStatus
void updateRefereeStatus(bool status)
Definition: command_sender.h:443
rm_common::DoubleBarrelCommandSender::jointStateCallback
void jointStateCallback(const sensor_msgs::JointState::ConstPtr &data)
Definition: command_sender.h:1092
rm_common::Vel3DCommandSender
Definition: command_sender.h:654
rm_common::BalanceCommandSender::BalanceCommandSender
BalanceCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:613
rm_common::CommandSenderBase::updatePowerHeatData
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition: command_sender.h:164
rm_common::ChassisCommandSender::accel_y_
LinearInterp accel_y_
Definition: command_sender.h:315
rm_common::Vel2DCommandSender
Definition: command_sender.h:177
rm_common::PowerLimit::setLimitPower
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition: power_limit.h:184
rm_common::Vel3DCommandSender::max_linear_x_
double max_linear_x_
Definition: command_sender.h:695
rm_common::HeaderStampCommandSenderBase
Definition: command_sender.h:164
rm_common::JointPositionBinaryCommandSender::changePosition
void changePosition(double scale)
Definition: command_sender.h:715
rm_common::DoubleBarrelCommandSender::updateSuggestFireData
void updateSuggestFireData(const std_msgs::Bool &data)
Definition: command_sender.h:965
rm_common::DoubleBarrelCommandSender::switchBarrel
void switchBarrel()
Definition: command_sender.h:1036
rm_common::BalanceCommandSender::setZero
void setZero() override
Definition: command_sender.h:625
rm_common::JointPositionBinaryCommandSender::per_change_position_
double per_change_position_
Definition: command_sender.h:733
rm_common::ShooterCommandSender::raiseSpeed
void raiseSpeed()
Definition: command_sender.h:571
rm_common::CardCommandSender::off_pos_
double off_pos_
Definition: command_sender.h:771
rm_common::DoubleBarrelCommandSender::getSpeed
double getSpeed()
Definition: command_sender.h:1022
rm_common::Vel3DCommandSender::setAngularVel
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition: command_sender.h:678
rm_common::JointPositionBinaryCommandSender::on_pos_
double on_pos_
Definition: command_sender.h:733
rm_common::CommandSenderBase::queue_size_
uint32_t queue_size_
Definition: command_sender.h:175
rm_common::CameraSwitchCommandSender::switchCamera
void switchCamera()
Definition: command_sender.h:860
rm_common::GimbalCommandSender::setUseRc
void setUseRc(bool flag)
Definition: command_sender.h:375
ros_utilities.h
rm_common::DoubleBarrelCommandSender::is_double_barrel_
bool is_double_barrel_
Definition: command_sender.h:1102
rm_common::JointPositionBinaryCommandSender::JointPositionBinaryCommandSender
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:701
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
rm_common::ShooterCommandSender::speed_10_
double speed_10_
Definition: command_sender.h:591
rm_common::CardCommandSender::CardCommandSender
CardCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:739
rm_common::Vel2DCommandSender::target_vel_yaw_threshold_
double target_vel_yaw_threshold_
Definition: command_sender.h:252
rm_common::MultiDofCommandSender::~MultiDofCommandSender
~MultiDofCommandSender()=default
rm_common::ChassisCommandSender::updateGameRobotStatus
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition: command_sender.h:283
rm_common::DoubleBarrelCommandSender::trigger_state_sub_
ros::Subscriber trigger_state_sub_
Definition: command_sender.h:1099
rm_common::HeatLimit::getShootFrequency
double getShootFrequency() const
Definition: heat_limit.h:194
rm_common::CommandSenderBase::updateGameRobotStatus
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition: command_sender.h:155
rm_common::CommandSenderBase::msg_
MsgType msg_
Definition: command_sender.h:177
rm_common::Vel2DCommandSender::setAngularZVel
void setAngularZVel(double scale)
Definition: command_sender.h:214
rm_common::ChassisCommandSender::setZero
void setZero() override
Definition: command_sender.h:311
rm_common::DoubleBarrelCommandSender::updateRefereeStatus
void updateRefereeStatus(bool status)
Definition: command_sender.h:950
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rm_common::JointJogCommandSender::JointJogCommandSender
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition: command_sender.h:777
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rm_common::JointJogCommandSender::minus
void minus()
Definition: command_sender.h:799
rm_common::DoubleBarrelCommandSender::last_push_time_
ros::Time last_push_time_
Definition: command_sender.h:1103
rm_common::GimbalCommandSender::setRate
void setRate(double scale_yaw, double scale_pitch)
Definition: command_sender.h:337
rm_common::JointPointCommandSender::JointPointCommandSender
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition: command_sender.h:821
rm_common::JointPointCommandSender::getIndex
int getIndex()
Definition: command_sender.h:830
rm_common::DoubleBarrelCommandSender::trigger_error_
double trigger_error_
Definition: command_sender.h:1105
rm_common::CommandSenderBase::getMsg
MsgType * getMsg()
Definition: command_sender.h:168
rm_common::ShooterCommandSender::speed_oscillation_
double speed_oscillation_
Definition: command_sender.h:593
rm_common::GimbalCommandSender::max_yaw_vel_
double max_yaw_vel_
Definition: command_sender.h:389
filters.h
rm_common::HeatLimit::setStatusOfShooter
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition: heat_limit.h:167
rm_common::ShooterCommandSender::updatePowerHeatData
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition: command_sender.h:439
rm_common::PowerLimit::setRefereeStatus
void setRefereeStatus(bool status)
Definition: power_limit.h:175
rm_common::JointPositionBinaryCommandSender::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:725
rm_common::JointPositionBinaryCommandSender::current_position_
double current_position_
Definition: command_sender.h:733
rm_common::TimeStampCommandSenderBase::TimeStampCommandSenderBase
TimeStampCommandSenderBase(ros::NodeHandle &nh)
Definition: command_sender.h:153
rm_common::Vel3DCommandSender::max_linear_y_
double max_linear_y_
Definition: command_sender.h:695
rm_common::HeatLimit::setRefereeStatus
void setRefereeStatus(bool status)
Definition: heat_limit.h:189
rm_common::ShooterCommandSender::dropSpeed
void dropSpeed()
Definition: command_sender.h:567
rm_common::GimbalCommandSender
Definition: command_sender.h:318
rm_common::LegCommandSender::setZero
void setZero() override
Definition: command_sender.h:651
rm_common::DoubleBarrelCommandSender::frequency_threshold_
double frequency_threshold_
Definition: command_sender.h:1108
rm_common::CameraSwitchCommandSender::setZero
void setZero() override
Definition: command_sender.h:868
rm_common::JointPositionBinaryCommandSender::getState
bool getState() const
Definition: command_sender.h:721
rm_common::LegCommandSender::getLgeLength
double getLgeLength()
Definition: command_sender.h:647
rm_common::PowerLimit
Definition: power_limit.h:80
rm_common::DoubleBarrelCommandSender::is_id1_
bool is_id1_
Definition: command_sender.h:1106
rm_common::DoubleBarrelCommandSender::id2_point_
double id2_point_
Definition: command_sender.h:1107
rm_common::ShooterCommandSender::~ShooterCommandSender
~ShooterCommandSender()
Definition: command_sender.h:430
rm_common::Vel3DCommandSender::setLinearVel
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition: command_sender.h:672
rm_common::CommandSenderBase::setZero
virtual void setZero()=0
rm_common::JointPositionBinaryCommandSender::change_position_
double change_position_
Definition: command_sender.h:733
rm_common::BalanceCommandSender
Definition: command_sender.h:610
rm_common::CameraSwitchCommandSender::camera1_name_
std::string camera1_name_
Definition: command_sender.h:871
rm_common::ShooterCommandSender::track_buff_error_tolerance_
double track_buff_error_tolerance_
Definition: command_sender.h:595
rm_common::CameraSwitchCommandSender
Definition: command_sender.h:852
rm_common::GimbalCommandSender::setPoint
void setPoint(geometry_msgs::PointStamped point)
Definition: command_sender.h:383
rm_common::ShooterCommandSender::getWheelSpeedDes
double getWheelSpeedDes()
Definition: command_sender.h:521
rm_common::ChassisCommandSender::power_limit_
PowerLimit * power_limit_
Definition: command_sender.h:311
rm_common::GimbalCommandSender::setZero
void setZero() override
Definition: command_sender.h:362
rm_common::CardCommandSender::long_pos_
double long_pos_
Definition: command_sender.h:771
std_msgs
rm_common::ShooterCommandSender::wheel_speed_30_
double wheel_speed_30_
Definition: command_sender.h:592
rm_common::HeatLimit::setCoolingHeatOfShooter
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition: heat_limit.h:173
rm_common::DoubleBarrelCommandSender::sendCommand
void sendCommand(const ros::Time &time)
Definition: command_sender.h:988
rm_common::CommandSenderBase::setMode
void setMode(int mode)
Definition: command_sender.h:146
rm_common::ShooterCommandSender::getSpeed
double getSpeed()
Definition: command_sender.h:516
rm_common::CardCommandSender::state
bool state
Definition: command_sender.h:770
rm_common::DoubleBarrelCommandSender::last_switch_time_
ros::Time last_switch_time_
Definition: command_sender.h:1103
rm_common::DoubleBarrelCommandSender::ready_duration_
double ready_duration_
Definition: command_sender.h:1104
rm_common::TimeStampCommandSenderBase
Definition: command_sender.h:150
rm_common::ShooterCommandSender::speed_18_
double speed_18_
Definition: command_sender.h:591
rm_common::JointPointCommandSender::joint_
std::string joint_
Definition: command_sender.h:847
rm_common::LegCommandSender::setLgeLength
void setLgeLength(double length)
Definition: command_sender.h:639
rm_common
Definition: calibration_queue.h:43
rm_common::ChassisCommandSender::accel_z_
LinearInterp accel_z_
Definition: command_sender.h:315
rm_common::GimbalCommandSender::GimbalCommandSender
GimbalCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:321
rm_common::CommandSenderBase::updateGameStatus
virtual void updateGameStatus(const rm_msgs::GameStatus data)
Definition: command_sender.h:158
rm_common::ShooterCommandSender::shoot_data_
rm_msgs::ShootData shoot_data_
Definition: command_sender.h:605
rm_common::CardCommandSender::long_on
void long_on()
Definition: command_sender.h:744
rm_common::DoubleBarrelCommandSender::checkSwitch
bool checkSwitch()
Definition: command_sender.h:1065
rm_common::JointPositionBinaryCommandSender::on
void on()
Definition: command_sender.h:705
rm_common::DoubleBarrelCommandSender::is_switching_
bool is_switching_
Definition: command_sender.h:1102
rm_common::LegCommandSender::LegCommandSender
LegCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:631
rm_common::DoubleBarrelCommandSender::updateGameRobotStatus
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition: command_sender.h:940
rm_common::ShooterCommandSender::suggest_fire_
std_msgs::Bool suggest_fire_
Definition: command_sender.h:606
rm_common::Vel3DCommandSender::max_linear_z_
double max_linear_z_
Definition: command_sender.h:695
rm_common::DoubleBarrelCommandSender::updateGimbalDesError
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition: command_sender.h:955
rm_common::ShooterCommandSender::last_bullet_speed_
double last_bullet_speed_
Definition: command_sender.h:593
rm_common::TimeStampCommandSenderBase::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:156
rm_common::JointPointCommandSender
Definition: command_sender.h:818
rm_common::MultiDofCommandSender::time_
ros::Time time_
Definition: command_sender.h:910
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rm_common::Vel2DCommandSender::setLinearXVel
void setLinearXVel(double scale)
Definition: command_sender.h:206
rm_common::CommandSenderBase::updateCapacityData
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition: command_sender.h:161
rm_common::GimbalCommandSender::eject_flag_
bool eject_flag_
Definition: command_sender.h:391
rm_common::ChassisCommandSender::updateRefereeStatus
void updateRefereeStatus(bool status)
Definition: command_sender.h:295
rm_common::CommandSenderBase::sendCommand
virtual void sendCommand(const ros::Time &time)
Definition: command_sender.h:151
rm_common::ShooterCommandSender::updateTrackData
void updateTrackData(const rm_msgs::TrackData &data)
Definition: command_sender.h:455
rm_common::JointJogCommandSender::joint_state_
const sensor_msgs::JointState & joint_state_
Definition: command_sender.h:814
rm_common::ShooterCommandSender::speed_limit_
double speed_limit_
Definition: command_sender.h:591
rm_common::ShooterCommandSender::checkError
void checkError(const ros::Time &time)
Definition: command_sender.h:485
rm_common::GimbalCommandSender::eject_sensitivity_
double eject_sensitivity_
Definition: command_sender.h:389
rm_common::Vel2DCommandSender::max_angular_z_
LinearInterp max_angular_z_
Definition: command_sender.h:250
rm_common::Vel2DCommandSender::updateTrackData
void updateTrackData(const rm_msgs::TrackData &data)
Definition: command_sender.h:202
rm_common::DoubleBarrelCommandSender::setArmorType
void setArmorType(uint8_t armor_type)
Definition: command_sender.h:1009
rm_common::HeatLimit::setShootFrequency
void setShootFrequency(uint8_t mode)
Definition: heat_limit.h:234
rm_common::DoubleBarrelCommandSender::joint_state_
sensor_msgs::JointState joint_state_
Definition: command_sender.h:1101
rm_common::DoubleBarrelCommandSender::checkError
void checkError(const ros::Time &time)
Definition: command_sender.h:984
rm_common::ShooterCommandSender::shoot_beforehand_cmd_
rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_
Definition: command_sender.h:604
rm_common::ShooterCommandSender::auto_wheel_speed_
bool auto_wheel_speed_
Definition: command_sender.h:601
rm_common::DoubleBarrelCommandSender::shooter_ID2_cmd_sender_
ShooterCommandSender * shooter_ID2_cmd_sender_
Definition: command_sender.h:1097
rm_common::GimbalCommandSender::time_constant_rc_
double time_constant_rc_
Definition: command_sender.h:390
rm_common::ShooterCommandSender::total_extra_wheel_speed_
double total_extra_wheel_speed_
Definition: command_sender.h:600
rm_common::CardCommandSender::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:763
rm_common::HeatLimit::getShootFrequencyMode
bool getShootFrequencyMode() const
Definition: heat_limit.h:239
rm_common::DoubleBarrelCommandSender::check_launch_threshold_
double check_launch_threshold_
Definition: command_sender.h:1109
rm_common::ShooterCommandSender::updateShootData
void updateShootData(const rm_msgs::ShootData &data)
Definition: command_sender.h:463
rm_common::Vel2DCommandSender::setZero
void setZero() override
Definition: command_sender.h:237
rm_common::JointPointCommandSender::index_
int index_
Definition: command_sender.h:848
rm_common::JointJogCommandSender::step_
double step_
Definition: command_sender.h:815
rm_common::ShooterCommandSender::wheel_speed_des_
double wheel_speed_des_
Definition: command_sender.h:593
rm_common::ShooterCommandSender::wheel_speed_10_
double wheel_speed_10_
Definition: command_sender.h:592
rm_common::CardCommandSender::off
void off()
Definition: command_sender.h:754
rm_common::MultiDofCommandSender::MultiDofCommandSender
MultiDofCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:877
rm_common::GimbalCommandSender::setEject
void setEject(bool flag)
Definition: command_sender.h:371
rm_common::ShooterCommandSender::max_track_target_vel_
double max_track_target_vel_
Definition: command_sender.h:597
rm_common::ShooterCommandSender::wheel_speed_16_
double wheel_speed_16_
Definition: command_sender.h:592
rm_common::ShooterCommandSender::wheel_speed_18_
double wheel_speed_18_
Definition: command_sender.h:592
rm_common::JointPositionBinaryCommandSender::state
bool state
Definition: command_sender.h:732
ros::Time
rm_common::JointPointCommandSender::setPoint
void setPoint(double point)
Definition: command_sender.h:826
rm_common::Vel3DCommandSender::max_angular_z_
double max_angular_z_
Definition: command_sender.h:695
rm_common::ShooterCommandSender::setArmorType
void setArmorType(uint8_t armor_type)
Definition: command_sender.h:575
rm_common::HeaderStampCommandSenderBase::HeaderStampCommandSenderBase
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
Definition: command_sender.h:167
rm_common::ShooterCommandSender::speed_16_
double speed_16_
Definition: command_sender.h:591
rm_common::PowerLimit::setCapacityData
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition: power_limit.h:169
rm_common::DoubleBarrelCommandSender
Definition: command_sender.h:913
getParam
T getParam(ros::NodeHandle &pnh, const std::string &param_name, const T &default_val)
Definition: ros_utilities.h:44
rm_common::ShooterCommandSender::extra_wheel_speed_once_
double extra_wheel_speed_once_
Definition: command_sender.h:599
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
rm_common::CommandSenderBase::pub_
ros::Publisher pub_
Definition: command_sender.h:176
rm_common::ShooterCommandSender::ShooterCommandSender
ShooterCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:397
rm_common::ChassisCommandSender::sendChassisCommand
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition: command_sender.h:303
ROS_ERROR
#define ROS_ERROR(...)
rm_common::ShooterCommandSender::setShootFrequency
void setShootFrequency(uint8_t mode)
Definition: command_sender.h:579
rm_common::PowerLimit::setGameRobotData
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition: power_limit.h:160
rm_common::JointPointCommandSender::setZero
void setZero() override
Definition: command_sender.h:844
rm_common::JointJogCommandSender::reset
void reset()
Definition: command_sender.h:783
rm_common::Vel3DCommandSender::max_angular_y_
double max_angular_y_
Definition: command_sender.h:695
rm_common::DoubleBarrelCommandSender::updatePowerHeatData
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition: command_sender.h:945
rm_common::GimbalCommandSender::use_rc_
bool use_rc_
Definition: command_sender.h:391
rm_common::DoubleBarrelCommandSender::triggerStateCallback
void triggerStateCallback(const control_msgs::JointControllerState::ConstPtr &data)
Definition: command_sender.h:1088
power_limit.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rm_common::Vel2DCommandSender::vel_direction_
double vel_direction_
Definition: command_sender.h:253
rm_common::JointJogCommandSender::joint_
std::string joint_
Definition: command_sender.h:813
rm_common::DoubleBarrelCommandSender::need_switch_
bool need_switch_
Definition: command_sender.h:1102
rm_common::ShooterCommandSender::gimbal_des_error_
rm_msgs::GimbalDesError gimbal_des_error_
Definition: command_sender.h:603
rm_common::GimbalCommandSender::time_constant_pc_
double time_constant_pc_
Definition: command_sender.h:390
rm_common::DoubleBarrelCommandSender::joint_state_sub_
ros::Subscriber joint_state_sub_
Definition: command_sender.h:1100
rm_common::CameraSwitchCommandSender::camera2_name_
std::string camera2_name_
Definition: command_sender.h:871
rm_common::PowerLimit::updateSafetyPower
void updateSafetyPower(int safety_power)
Definition: power_limit.h:143
rm_common::ChassisCommandSender::updatePowerHeatData
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition: command_sender.h:287
rm_common::Vel2DCommandSender::setLinearYVel
void setLinearYVel(double scale)
Definition: command_sender.h:210
rm_common::Vel2DCommandSender::track_data_
rm_msgs::TrackData track_data_
Definition: command_sender.h:255
rm_common::Vel3DCommandSender::max_angular_x_
double max_angular_x_
Definition: command_sender.h:695
rm_common::GimbalCommandSender::setBulletSpeed
void setBulletSpeed(double bullet_speed)
Definition: command_sender.h:367
rm_common::DoubleBarrelCommandSender::DoubleBarrelCommandSender
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:916
rm_common::GimbalCommandSender::~GimbalCommandSender
~GimbalCommandSender()=default
rm_common::DoubleBarrelCommandSender::switching_duration_
double switching_duration_
Definition: command_sender.h:1104
rm_common::DoubleBarrelCommandSender::updateTrackData
void updateTrackData(const rm_msgs::TrackData &data)
Definition: command_sender.h:960
rm_common::GimbalCommandSender::track_timeout_
double track_timeout_
Definition: command_sender.h:389
rm_common::Vel2DCommandSender::Vel2DCommandSender
Vel2DCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:180
rm_common::ShooterCommandSender::getShootFrequency
uint8_t getShootFrequency()
Definition: command_sender.h:583
rm_common::ShooterCommandSender::setSpeedDesAndWheelSpeedDes
void setSpeedDesAndWheelSpeedDes()
Definition: command_sender.h:526
rm_common::DoubleBarrelCommandSender::init
void init()
Definition: command_sender.h:999
rm_common::HeaderStampCommandSenderBase::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:170
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
rm_common::DoubleBarrelCommandSender::shooter_ID1_cmd_sender_
ShooterCommandSender * shooter_ID1_cmd_sender_
Definition: command_sender.h:1096
rm_common::ChassisCommandSender::updateCapacityData
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition: command_sender.h:291
rm_common::JointPointCommandSender::joint_state_
const sensor_msgs::JointState & joint_state_
Definition: command_sender.h:849
rm_common::DoubleBarrelCommandSender::setMode
void setMode(int mode)
Definition: command_sender.h:976
rm_common::DoubleBarrelCommandSender::updateShootBeforehandCmd
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition: command_sender.h:970
rm_common::CardCommandSender::short_on
void short_on()
Definition: command_sender.h:749
rm_common::ShooterCommandSender::speed_des_
double speed_des_
Definition: command_sender.h:591
ROS_INFO
#define ROS_INFO(...)
rm_common::PowerLimit::setChassisPowerBuffer
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition: power_limit.h:165
rm_common::ChassisCommandSender::setFollowVelDes
void setFollowVelDes(double follow_vel_des)
Definition: command_sender.h:299
ROS_ASSERT
#define ROS_ASSERT(cond)
rm_common::ShooterCommandSender::updateSuggestFireData
void updateSuggestFireData(const std_msgs::Bool &data)
Definition: command_sender.h:459
linear_interpolation.h
rm_common::CardCommandSender
Definition: command_sender.h:736
rm_common::DoubleBarrelCommandSender::id1_point_
double id1_point_
Definition: command_sender.h:1107
rm_common::LinearInterp::init
void init(XmlRpc::XmlRpcValue &config)
Definition: linear_interpolation.h:15
ros::Duration
rm_common::CameraSwitchCommandSender::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:864
rm_common::BalanceCommandSender::setBalanceMode
void setBalanceMode(const int mode)
Definition: command_sender.h:617
rm_common::DoubleBarrelCommandSender::barrel_command_sender_
JointPointCommandSender * barrel_command_sender_
Definition: command_sender.h:1098
rm_common::DoubleBarrelCommandSender::checklaunch
void checklaunch()
Definition: command_sender.h:1052
rm_common::GimbalCommandSender::setGimbalTraj
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition: command_sender.h:357
rm_common::ShooterCommandSender::untrack_armor_error_tolerance_
double untrack_armor_error_tolerance_
Definition: command_sender.h:596
rm_common::Vel2DCommandSender::set2DVel
void set2DVel(double scale_x, double scale_y, double scale_z)
Definition: command_sender.h:231
rm_common::ShooterCommandSender::speed_30_
double speed_30_
Definition: command_sender.h:591
rm_common::JointPositionBinaryCommandSender::setZero
void setZero() override
Definition: command_sender.h:729
rm_common::ShooterCommandSender::sendCommand
void sendCommand(const ros::Time &time) override
Definition: command_sender.h:510
XmlRpc::XmlRpcValue
rm_common::ShooterCommandSender::updateShootBeforehandCmd
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition: command_sender.h:451
rm_common::ChassisCommandSender::ChassisCommandSender
ChassisCommandSender(ros::NodeHandle &nh)
Definition: command_sender.h:261
ros::NodeHandle
ros::Subscriber
rm_common::ShooterCommandSender::heat_limit_
HeatLimit * heat_limit_
Definition: command_sender.h:588
ros::Time::now
static Time now()
rm_common::ShooterCommandSender::target_acceleration_tolerance_
double target_acceleration_tolerance_
Definition: command_sender.h:598


rm_common
Author(s):
autogenerated on Wed Apr 9 2025 02:22:16