rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
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
71namespace rm_common
72{
73template <class MsgType>
75{
76public:
77 explicit CommandSenderBase(ros::NodeHandle& nh)
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
111protected:
112 std::string topic_;
113 uint32_t queue_size_;
114 ros::Publisher pub_;
115 MsgType msg_;
116};
117
118template <class MsgType>
120{
121public:
122 explicit TimeStampCommandSenderBase(ros::NodeHandle& nh) : CommandSenderBase<MsgType>(nh)
123 {
124 }
125 void sendCommand(const ros::Time& time) override
126 {
129 }
130};
131
132template <class MsgType>
134{
135public:
136 explicit HeaderStampCommandSenderBase(ros::NodeHandle& nh) : CommandSenderBase<MsgType>(nh)
137 {
138 }
139 void sendCommand(const ros::Time& time) override
140 {
141 CommandSenderBase<MsgType>::msg_.header.stamp = time;
143 }
144};
145
146class Vel2DCommandSender : public CommandSenderBase<geometry_msgs::Twist>
147{
148public:
149 explicit Vel2DCommandSender(ros::NodeHandle& nh) : CommandSenderBase<geometry_msgs::Twist>(nh)
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.;
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
213protected:
214 void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr& msg)
215 {
216 power_limit_ = msg->power_limit;
217 }
218
220 double power_limit_ = 0.;
222 double vel_direction_ = 1.;
224 rm_msgs::TrackData track_data_;
225};
226
227class ChassisCommandSender : public TimeStampCommandSenderBase<rm_msgs::ChassisCmd>
228{
229public:
230 explicit ChassisCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::ChassisCmd>(nh)
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 {
250 power_limit_->updateSafetyPower(safety_power);
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 {
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{};
282
283private:
284 LinearInterp accel_x_, accel_y_, accel_z_;
285};
286
287class GimbalCommandSender : public TimeStampCommandSenderBase<rm_msgs::GimbalCmd>
288{
289public:
290 explicit GimbalCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::GimbalCmd>(nh)
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_))
303 eject_sensitivity_ = 1.;
304 }
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 setGimbalTrajFrameId(std::string traj_frame_id)
332 {
333 msg_.traj_frame_id = traj_frame_id;
334 }
335 void setZero() override
336 {
337 msg_.rate_yaw = 0.;
338 msg_.rate_pitch = 0.;
339 }
340 void setBulletSpeed(double bullet_speed)
341 {
342 msg_.bullet_speed = bullet_speed;
343 }
344 void setEject(bool flag)
345 {
346 eject_flag_ = flag;
347 }
348 void setUseRc(bool flag)
349 {
350 use_rc_ = flag;
351 }
352 bool getEject() const
353 {
354 return eject_flag_;
355 }
356 void setPoint(geometry_msgs::PointStamped point)
357 {
358 msg_.target_pos = point;
359 }
360
361private:
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_{};
365};
366
367class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd>
368{
369public:
370 explicit ShooterCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::ShootCmd>(nh)
371 {
372 ros::NodeHandle limit_nh(nh, "heat_limit");
373 heat_limit_ = new HeatLimit(limit_nh);
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_))
389 {
390 target_acceleration_tolerance_ = 0.;
391 ROS_INFO("target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
392 }
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_))
398 {
399 max_track_target_vel_ = 9.0;
400 ROS_ERROR("max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
401 }
402 }
404 {
405 delete heat_limit_;
406 }
407
408 void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
409 {
411 }
412 void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
413 {
415 }
416 void updateRefereeStatus(bool status)
417 {
419 }
420 void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
421 {
422 gimbal_des_error_ = error;
423 }
424 void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
425 {
426 shoot_beforehand_cmd_ = data;
427 }
428 void updateTrackData(const rm_msgs::TrackData& data)
429 {
430 track_data_ = data;
431 }
432 void updateSuggestFireData(const std_msgs::Bool& data)
433 {
434 suggest_fire_ = data;
435 }
436 void updateShootData(const rm_msgs::ShootData& data)
437 {
438 shoot_data_ = data;
439 if (auto_wheel_speed_)
440 {
441 if (last_bullet_speed_ == 0.0)
442 last_bullet_speed_ = speed_des_;
443 if (shoot_data_.bullet_speed != last_bullet_speed_)
444 {
445 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
446 {
447 total_extra_wheel_speed_ -= 5.0;
448 }
449 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
450 {
451 total_extra_wheel_speed_ += 5.0;
452 }
453 }
454 if (shoot_data_.bullet_speed != 0.0)
455 last_bullet_speed_ = shoot_data_.bullet_speed;
456 }
457 }
458 void checkError(const ros::Time& time)
459 {
460 if (msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
461 {
462 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
463 return;
464 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
465 {
466 setMode(rm_msgs::ShootCmd::READY);
467 return;
468 }
469 }
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_;
475 else
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);
482 }
483 void sendCommand(const ros::Time& time) override
484 {
485 msg_.wheel_speed = getWheelSpeedDes();
488 }
489 double getSpeed()
490 {
492 return speed_des_;
493 }
495 {
497 return wheel_speed_des_ + total_extra_wheel_speed_;
498 }
500 {
501 switch (heat_limit_->getSpeedLimit())
502 {
503 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
504 {
505 speed_limit_ = 10.0;
506 speed_des_ = speed_10_;
507 wheel_speed_des_ = wheel_speed_10_;
508 break;
509 }
510 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
511 {
512 speed_limit_ = 15.0;
513 speed_des_ = speed_15_;
514 wheel_speed_des_ = wheel_speed_15_;
515 break;
516 }
517 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
518 {
519 speed_limit_ = 16.0;
520 speed_des_ = speed_16_;
521 wheel_speed_des_ = wheel_speed_16_;
522 break;
523 }
524 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
525 {
526 speed_limit_ = 18.0;
527 speed_des_ = speed_18_;
528 wheel_speed_des_ = wheel_speed_18_;
529 break;
530 }
531 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
532 {
533 speed_limit_ = 30.0;
534 speed_des_ = speed_30_;
535 wheel_speed_des_ = wheel_speed_30_;
536 break;
537 }
538 }
539 }
541 {
542 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
543 }
545 {
546 total_extra_wheel_speed_ += extra_wheel_speed_once_;
547 }
548 void setArmorType(uint8_t armor_type)
549 {
550 armor_type_ = armor_type;
551 }
552 void setShootFrequency(uint8_t mode)
553 {
555 }
557 {
559 }
560 void setZero() override{};
562
563private:
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_{};
581};
582
583class BalanceCommandSender : public CommandSenderBase<std_msgs::UInt8>
584{
585public:
586 explicit BalanceCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::UInt8>(nh)
587 {
588 }
589
590 void setBalanceMode(const int mode)
591 {
592 msg_.data = mode;
593 }
595 {
596 return msg_.data;
597 }
598 void setZero() override{};
599};
600
601class LegCommandSender : public CommandSenderBase<rm_msgs::LegCmd>
602{
603public:
604 explicit LegCommandSender(ros::NodeHandle& nh) : CommandSenderBase<rm_msgs::LegCmd>(nh)
605 {
606 }
607
608 void setJump(bool jump)
609 {
610 msg_.jump = jump;
611 }
612 void setLgeLength(double length)
613 {
614 msg_.leg_length = length;
615 }
616 bool getJump()
617 {
618 return msg_.jump;
619 }
621 {
622 return msg_.leg_length;
623 }
624 void setZero() override{};
625};
626
627class Vel3DCommandSender : public HeaderStampCommandSenderBase<geometry_msgs::TwistStamped>
628{
629public:
630 explicit Vel3DCommandSender(ros::NodeHandle& nh) : HeaderStampCommandSenderBase(nh)
631 {
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());
644 }
645 void setLinearVel(double scale_x, double scale_y, double scale_z)
646 {
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;
650 }
651 void setAngularVel(double scale_x, double scale_y, double scale_z)
652 {
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;
656 }
657 void setZero() override
658 {
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.;
665 }
666
667private:
668 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
669};
670
672{
673public:
674 explicit JointPositionBinaryCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::Float64>(nh)
675 {
676 ROS_ASSERT(nh.getParam("on_pos", on_pos_) && nh.getParam("off_pos", off_pos_));
677 }
678 void on()
679 {
680 msg_.data = on_pos_;
681 state = true;
682 }
683 void off()
684 {
685 msg_.data = off_pos_;
686 state = false;
687 }
688 void changePosition(double scale)
689 {
690 current_position_ = msg_.data;
691 change_position_ = current_position_ + scale * per_change_position_;
692 msg_.data = change_position_;
693 }
694 bool getState() const
695 {
696 return state;
697 }
698 void sendCommand(const ros::Time& time) override
699 {
701 }
702 void setZero() override{};
703
704private:
705 bool state{};
706 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
707};
708
709class CardCommandSender : public CommandSenderBase<std_msgs::Float64>
710{
711public:
712 explicit CardCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::Float64>(nh)
713 {
714 ROS_ASSERT(nh.getParam("long_pos", long_pos_) && nh.getParam("short_pos", short_pos_) &&
715 nh.getParam("off_pos", off_pos_));
716 }
717 void long_on()
718 {
719 msg_.data = long_pos_;
720 state = true;
721 }
722 void short_on()
723 {
724 msg_.data = short_pos_;
725 state = true;
726 }
727 void off()
728 {
729 msg_.data = off_pos_;
730 state = false;
731 }
732 bool getState() const
733 {
734 return state;
735 }
736 void sendCommand(const ros::Time& time) override
737 {
739 }
740 void setZero() override{};
741
742private:
743 bool state{};
744 double long_pos_{}, short_pos_{}, off_pos_{};
745};
746
747class JointJogCommandSender : public CommandSenderBase<std_msgs::Float64>
748{
749public:
750 explicit JointJogCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
751 : CommandSenderBase<std_msgs::Float64>(nh), joint_state_(joint_state)
752 {
753 ROS_ASSERT(nh.getParam("joint", joint_));
754 ROS_ASSERT(nh.getParam("step", step_));
755 }
756 void reset()
757 {
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)];
761 else
762 msg_.data = NAN;
763 }
764 void plus()
765 {
766 if (msg_.data != NAN)
767 {
768 msg_.data += step_;
769 sendCommand(ros::Time());
770 }
771 }
772 void minus()
773 {
774 if (msg_.data != NAN)
775 {
776 msg_.data -= step_;
777 sendCommand(ros::Time());
778 }
779 }
780 const std::string& getJoint()
781 {
782 return joint_;
783 }
784
785private:
786 std::string joint_{};
787 const sensor_msgs::JointState& joint_state_;
788 double step_{};
789};
790
791class JointPointCommandSender : public CommandSenderBase<std_msgs::Float64>
792{
793public:
794 explicit JointPointCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
795 : CommandSenderBase<std_msgs::Float64>(nh), joint_state_(joint_state)
796 {
797 ROS_ASSERT(nh.getParam("joint", joint_));
798 }
799 void setPoint(double point)
800 {
801 msg_.data = point;
802 }
804 {
805 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
806 if (i != joint_state_.name.end())
807 {
808 index_ = std::distance(joint_state_.name.begin(), i);
809 return index_;
810 }
811 else
812 {
813 ROS_ERROR("Can not find joint %s", joint_.c_str());
814 return -1;
815 }
816 }
817 void setZero() override{};
818
819private:
820 std::string joint_{};
821 int index_{};
822 const sensor_msgs::JointState& joint_state_;
823};
824
825class CameraSwitchCommandSender : public CommandSenderBase<std_msgs::String>
826{
827public:
828 explicit CameraSwitchCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::String>(nh)
829 {
830 ROS_ASSERT(nh.getParam("camera1_name", camera1_name_) && nh.getParam("camera2_name", camera2_name_));
831 msg_.data = camera1_name_;
832 }
834 {
835 msg_.data = msg_.data == camera1_name_ ? camera2_name_ : camera1_name_;
836 }
837 void sendCommand(const ros::Time& time) override
838 {
840 }
841 void setZero() override{};
842
843private:
844 std::string camera1_name_{}, camera2_name_{};
845};
846
847class MultiDofCommandSender : public TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>
848{
849public:
850 explicit MultiDofCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>(nh)
851 {
852 }
854 void setMode(int mode)
855 {
856 msg_.mode = mode;
857 }
859 {
860 return msg_.mode;
861 }
862 void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y,
863 double angular_z)
864 {
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;
871 }
872 void setZero() override
873 {
874 msg_.linear.x = 0;
875 msg_.linear.y = 0;
876 msg_.linear.z = 0;
877 msg_.angular.x = 0;
878 msg_.angular.y = 0;
879 msg_.angular.z = 0;
880 }
881
882private:
883 ros::Time time_;
884};
885
887{
888public:
889 DoubleBarrelCommandSender(ros::NodeHandle& nh)
890 {
891 ros::NodeHandle shooter_ID1_nh(nh, "shooter_ID1");
892 shooter_ID1_cmd_sender_ = new ShooterCommandSender(shooter_ID1_nh);
893 ros::NodeHandle shooter_ID2_nh(nh, "shooter_ID2");
894 shooter_ID2_cmd_sender_ = new ShooterCommandSender(shooter_ID2_nh);
895 ros::NodeHandle barrel_nh(nh, "barrel");
896 barrel_command_sender_ = new rm_common::JointPointCommandSender(barrel_nh, joint_state_);
897
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_);
906
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);
911 }
912
913 void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
914 {
915 shooter_ID1_cmd_sender_->updateGameRobotStatus(data);
916 shooter_ID2_cmd_sender_->updateGameRobotStatus(data);
917 }
918 void updatePowerHeatData(const rm_msgs::PowerHeatData data)
919 {
920 shooter_ID1_cmd_sender_->heat_limit_->setCoolingHeatOfShooter(data);
921 shooter_ID2_cmd_sender_->heat_limit_->setCoolingHeatOfShooter(data);
922 }
923 void updateRefereeStatus(bool status)
924 {
925 shooter_ID1_cmd_sender_->updateRefereeStatus(status);
926 shooter_ID2_cmd_sender_->updateRefereeStatus(status);
927 }
928 void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
929 {
930 shooter_ID1_cmd_sender_->updateGimbalDesError(error);
931 shooter_ID2_cmd_sender_->updateGimbalDesError(error);
932 }
933 void updateTrackData(const rm_msgs::TrackData& data)
934 {
935 shooter_ID1_cmd_sender_->updateTrackData(data);
936 shooter_ID2_cmd_sender_->updateTrackData(data);
937 }
938 void updateSuggestFireData(const std_msgs::Bool& data)
939 {
940 shooter_ID1_cmd_sender_->updateSuggestFireData(data);
941 shooter_ID2_cmd_sender_->updateSuggestFireData(data);
942 }
943 void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
944 {
945 shooter_ID1_cmd_sender_->updateShootBeforehandCmd(data);
946 shooter_ID2_cmd_sender_->updateShootBeforehandCmd(data);
947 }
948
949 void setMode(int mode)
950 {
951 getBarrel()->setMode(mode);
952 }
953 void setZero()
954 {
955 getBarrel()->setZero();
956 }
957 void checkError(const ros::Time& time)
958 {
959 getBarrel()->checkError(time);
960 }
961 void sendCommand(const ros::Time& time)
962 {
963 if (checkSwitch())
964 need_switch_ = true;
965 if (need_switch_)
966 switchBarrel();
967 checklaunch();
968 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
969 last_push_time_ = time;
970 getBarrel()->sendCommand(time);
971 }
972 void init()
973 {
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);
978 barrel_command_sender_->sendCommand(time);
979 shooter_ID1_cmd_sender_->sendCommand(time);
980 shooter_ID2_cmd_sender_->sendCommand(time);
981 }
982 void setArmorType(uint8_t armor_type)
983 {
984 shooter_ID1_cmd_sender_->setArmorType(armor_type);
985 shooter_ID2_cmd_sender_->setArmorType(armor_type);
986 }
987 void setShootFrequency(uint8_t mode)
988 {
989 getBarrel()->setShootFrequency(mode);
990 }
992 {
993 return getBarrel()->getShootFrequency();
994 }
995 double getSpeed()
996 {
997 return getBarrel()->getSpeed();
998 }
999
1000private:
1001 ShooterCommandSender* getBarrel()
1002 {
1003 if (barrel_command_sender_->getMsg()->data == id1_point_)
1004 is_id1_ = true;
1005 else
1006 is_id1_ = false;
1007 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1008 }
1009 void switchBarrel()
1010 {
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_)
1015 {
1016 barrel_command_sender_->getMsg()->data == id2_point_ ? barrel_command_sender_->setPoint(id1_point_) :
1017 barrel_command_sender_->setPoint(id2_point_);
1018 barrel_command_sender_->sendCommand(time);
1019 last_switch_time_ = time;
1020 need_switch_ = false;
1021 is_switching_ = true;
1022 }
1023 }
1024
1025 void checklaunch()
1026 {
1027 ros::Time time = ros::Time::now();
1028 if (is_switching_)
1029 {
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;
1035 }
1036 }
1037
1038 bool checkSwitch()
1039 {
1040 if (!is_double_barrel_)
1041 return false;
1042 if (shooter_ID1_cmd_sender_->heat_limit_->getCoolingLimit() == 0 ||
1043 shooter_ID2_cmd_sender_->heat_limit_->getCoolingLimit() == 0)
1044 {
1045 ROS_WARN_ONCE("Can not get cooling limit");
1046 return false;
1047 }
1048 if (shooter_ID1_cmd_sender_->heat_limit_->getShootFrequency() < frequency_threshold_ ||
1049 shooter_ID2_cmd_sender_->heat_limit_->getShootFrequency() < frequency_threshold_)
1050 {
1051 if (getBarrel() == shooter_ID1_cmd_sender_)
1052 return getBarrel()->heat_limit_->getShootFrequency() < frequency_threshold_ &&
1053 shooter_ID2_cmd_sender_->heat_limit_->getShootFrequency() > frequency_threshold_;
1054 else
1055 return getBarrel()->heat_limit_->getShootFrequency() < frequency_threshold_ &&
1056 shooter_ID1_cmd_sender_->heat_limit_->getShootFrequency() > frequency_threshold_;
1057 }
1058 else
1059 return false;
1060 }
1061 void triggerStateCallback(const control_msgs::JointControllerState::ConstPtr& data)
1062 {
1063 trigger_error_ = data->error;
1064 }
1065 void jointStateCallback(const sensor_msgs::JointState::ConstPtr& data)
1066 {
1067 joint_state_ = *data;
1068 }
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_;
1083};
1084
1085} // namespace rm_common
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
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(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 &param_name, const T &default_val)
Definition ros_utilities.h:44