rm_control
Loading...
Searching...
No Matches
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/ChassisActiveSusCmd.h>
46#include <rm_msgs/GimbalCmd.h>
47#include <rm_msgs/ShootCmd.h>
48#include <rm_msgs/ShootBeforehandCmd.h>
49#include <rm_msgs/GimbalDesError.h>
50#include <rm_msgs/StateCmd.h>
51#include <rm_msgs/TrackData.h>
52#include <rm_msgs/GameRobotHp.h>
53#include <rm_msgs/StatusChangeRequest.h>
54#include <rm_msgs/ShootData.h>
55#include <rm_msgs/LegCmd.h>
56#include <geometry_msgs/TwistStamped.h>
57#include <sensor_msgs/JointState.h>
58#include <nav_msgs/Odometry.h>
59#include <std_msgs/UInt8.h>
60#include <std_msgs/Float64.h>
61#include <rm_msgs/MultiDofCmd.h>
62#include <std_msgs/String.h>
63#include <std_msgs/Bool.h>
64#include <control_msgs/JointControllerState.h>
65#include <std_msgs/Float32.h>
66
72
73namespace rm_common
74{
75namespace detail
76{
77template <typename TMsg>
78auto setTrajFrameIdIfSupported(TMsg& msg, const std::string& traj_frame_id, int)
79 -> decltype((void)(msg.traj_frame_id = traj_frame_id), void())
80{
81 msg.traj_frame_id = traj_frame_id;
82}
83
84template <typename TMsg>
85void setTrajFrameIdIfSupported(TMsg&, const std::string&, long)
86{
87}
88} // namespace detail
89
90template <class MsgType>
92{
93public:
94 explicit CommandSenderBase(ros::NodeHandle& nh)
95 {
96 if (!nh.getParam("topic", topic_))
97 ROS_ERROR("Topic name no defined (namespace: %s)", nh.getNamespace().c_str());
98 queue_size_ = getParam(nh, "queue_size", 1);
99 pub_ = nh.advertise<MsgType>(topic_, queue_size_);
100 }
101 void setMode(int mode)
102 {
103 if (!std::is_same<MsgType, geometry_msgs::Twist>::value && !std::is_same<MsgType, std_msgs::Float64>::value)
104 msg_.mode = mode;
105 }
106 virtual void sendCommand(const ros::Time& time)
107 {
108 pub_.publish(msg_);
109 }
110 virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
111 {
112 }
113 virtual void updateGameStatus(const rm_msgs::GameStatus data)
114 {
115 }
116 virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
117 {
118 }
119 virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
120 {
121 }
122 virtual void setZero() = 0;
123 MsgType* getMsg()
124 {
125 return &msg_;
126 }
127
128protected:
129 std::string topic_;
130 uint32_t queue_size_;
131 ros::Publisher pub_;
132 MsgType msg_;
133};
134
135template <class MsgType>
137{
138public:
139 explicit TimeStampCommandSenderBase(ros::NodeHandle& nh) : CommandSenderBase<MsgType>(nh)
140 {
141 }
142 void sendCommand(const ros::Time& time) override
143 {
146 }
147};
148
149template <class MsgType>
151{
152public:
153 explicit HeaderStampCommandSenderBase(ros::NodeHandle& nh) : CommandSenderBase<MsgType>(nh)
154 {
155 }
156 void sendCommand(const ros::Time& time) override
157 {
158 CommandSenderBase<MsgType>::msg_.header.stamp = time;
160 }
161};
162
163class Vel2DCommandSender : public CommandSenderBase<geometry_msgs::Twist>
164{
165public:
166 explicit Vel2DCommandSender(ros::NodeHandle& nh) : CommandSenderBase<geometry_msgs::Twist>(nh)
167 {
168 XmlRpc::XmlRpcValue xml_rpc_value;
169 if (!nh.getParam("max_linear_x", xml_rpc_value))
170 ROS_ERROR("Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
171 else
172 max_linear_x_.init(xml_rpc_value);
173 if (!nh.getParam("max_linear_y", xml_rpc_value))
174 ROS_ERROR("Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
175 else
176 max_linear_y_.init(xml_rpc_value);
177 if (!nh.getParam("max_angular_z", xml_rpc_value))
178 ROS_ERROR("Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
179 else
180 max_angular_z_.init(xml_rpc_value);
181 std::string topic;
182 nh.getParam("power_limit_topic", topic);
183 target_vel_yaw_threshold_ = getParam(nh, "target_vel_yaw_threshold", 3.);
185 nh.subscribe<rm_msgs::ChassisCmd>(topic, 1, &Vel2DCommandSender::chassisCmdCallback, this);
186 }
187
188 void updateTrackData(const rm_msgs::TrackData& data)
189 {
190 track_data_ = data;
191 }
192 void setLinearXVel(double scale)
193 {
194 msg_.linear.x = scale * max_linear_x_.output(power_limit_);
195 };
196 void setLinearYVel(double scale)
197 {
198 msg_.linear.y = scale * max_linear_y_.output(power_limit_);
199 };
200 void setAngularZVel(double scale)
201 {
203 vel_direction_ = -1.;
205 vel_direction_ = 1.;
207 };
208 void setAngularZVel(double scale, double limit)
209 {
211 vel_direction_ = -1.;
213 vel_direction_ = 1.;
214 double angular_z = max_angular_z_.output(power_limit_) > limit ? limit : max_angular_z_.output(power_limit_);
215 msg_.angular.z = scale * angular_z * vel_direction_;
216 };
217 void set2DVel(double scale_x, double scale_y, double scale_z)
218 {
219 setLinearXVel(scale_x);
220 setLinearYVel(scale_y);
221 setAngularZVel(scale_z);
222 }
223 void setZero() override
224 {
225 msg_.linear.x = 0.;
226 msg_.linear.y = 0.;
227 msg_.angular.z = 0.;
228 }
229
230protected:
231 void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr& msg)
232 {
233 power_limit_ = msg->power_limit;
234 }
235
237 double power_limit_ = 0.;
239 double vel_direction_ = 1.;
241 rm_msgs::TrackData track_data_;
242};
243
244class ChassisCommandSender : public TimeStampCommandSenderBase<rm_msgs::ChassisCmd>
245{
246public:
247 explicit ChassisCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::ChassisCmd>(nh)
248 {
249 XmlRpc::XmlRpcValue xml_rpc_value;
250 power_limit_ = new PowerLimit(nh);
251 if (!nh.getParam("accel_x", xml_rpc_value))
252 ROS_ERROR("Accel X no defined (namespace: %s)", nh.getNamespace().c_str());
253 else
254 accel_x_.init(xml_rpc_value);
255 if (!nh.getParam("accel_y", xml_rpc_value))
256 ROS_ERROR("Accel Y no defined (namespace: %s)", nh.getNamespace().c_str());
257 else
258 accel_y_.init(xml_rpc_value);
259 if (!nh.getParam("accel_z", xml_rpc_value))
260 ROS_ERROR("Accel Z no defined (namespace: %s)", nh.getNamespace().c_str());
261 else
262 accel_z_.init(xml_rpc_value);
263 }
264
265 void updateSafetyPower(int safety_power)
266 {
267 power_limit_->updateSafetyPower(safety_power);
268 }
269 void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
270 {
272 }
273 void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
274 {
276 }
277 void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
278 {
280 }
281 void updateRefereeStatus(bool status)
282 {
284 }
285 void setFollowVelDes(double follow_vel_des)
286 {
287 msg_.follow_vel_des = follow_vel_des;
288 }
289 void setWirelessState(bool state)
290 {
291 msg_.wireless_state = state;
292 }
293 void sendChassisCommand(const ros::Time& time, bool is_gyro)
294 {
296 msg_.accel.linear.x = accel_x_.output(msg_.power_limit);
297 msg_.accel.linear.y = accel_y_.output(msg_.power_limit);
298 msg_.accel.angular.z = accel_z_.output(msg_.power_limit);
300 }
301 void setZero() override{};
303
304private:
305 LinearInterp accel_x_, accel_y_, accel_z_;
306};
307
308class ChassisActiveSuspensionCommandSender : public TimeStampCommandSenderBase<rm_msgs::ChassisActiveSusCmd>
309{
310public:
311 explicit ChassisActiveSuspensionCommandSender(ros::NodeHandle& nh)
312 : TimeStampCommandSenderBase<rm_msgs::ChassisActiveSusCmd>(nh)
313 {
314 }
315 void setZero() override
316 {
317 msg_.mode = 0;
318 }
319};
320class GimbalCommandSender : public TimeStampCommandSenderBase<rm_msgs::GimbalCmd>
321{
322public:
323 explicit GimbalCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::GimbalCmd>(nh)
324 {
325 if (!nh.getParam("max_yaw_vel", max_yaw_vel_))
326 ROS_ERROR("Max yaw velocity no defined (namespace: %s)", nh.getNamespace().c_str());
327 if (!nh.getParam("max_pitch_vel", max_pitch_vel_))
328 ROS_ERROR("Max pitch velocity no defined (namespace: %s)", nh.getNamespace().c_str());
329 if (!nh.getParam("time_constant_rc", time_constant_rc_))
330 ROS_ERROR("Time constant rc no defined (namespace: %s)", nh.getNamespace().c_str());
331 if (!nh.getParam("time_constant_pc", time_constant_pc_))
332 ROS_ERROR("Time constant pc no defined (namespace: %s)", nh.getNamespace().c_str());
333 if (!nh.getParam("track_timeout", track_timeout_))
334 ROS_ERROR("Track timeout no defined (namespace: %s)", nh.getNamespace().c_str());
335 if (!nh.getParam("eject_sensitivity", eject_sensitivity_))
336 eject_sensitivity_ = 1.;
337 }
339 void setRate(double scale_yaw, double scale_pitch)
340 {
341 if (std::abs(scale_yaw) > 1)
342 scale_yaw = scale_yaw > 0 ? 1 : -1;
343 if (std::abs(scale_pitch) > 1)
344 scale_pitch = scale_pitch > 0 ? 1 : -1;
345 double time_constant{};
346 if (use_rc_)
347 time_constant = time_constant_rc_;
348 else
349 time_constant = time_constant_pc_;
350 msg_.rate_yaw = msg_.rate_yaw + (scale_yaw * max_yaw_vel_ - msg_.rate_yaw) * (0.001 / (time_constant + 0.001));
351 msg_.rate_pitch =
352 msg_.rate_pitch + (scale_pitch * max_pitch_vel_ - msg_.rate_pitch) * (0.001 / (time_constant + 0.001));
353 if (eject_flag_)
354 {
355 msg_.rate_yaw *= eject_sensitivity_;
356 msg_.rate_pitch *= eject_sensitivity_;
357 }
358 }
359 void setGimbalTraj(double traj_yaw, double traj_pitch)
360 {
361 msg_.traj_yaw = traj_yaw;
362 msg_.traj_pitch = traj_pitch;
363 }
364 void setTrajFrameId(const std::string& traj_frame_id)
365 {
366 detail::setTrajFrameIdIfSupported(msg_, traj_frame_id, 0);
367 }
368 void setZero() override
369 {
370 msg_.rate_yaw = 0.;
371 msg_.rate_pitch = 0.;
372 }
373 void setBulletSpeed(double bullet_speed)
374 {
375 msg_.bullet_speed = bullet_speed;
376 }
377 void setEject(bool flag)
378 {
379 eject_flag_ = flag;
380 }
381 void setUseRc(bool flag)
382 {
383 use_rc_ = flag;
384 }
385 bool getEject() const
386 {
387 return eject_flag_;
388 }
389 void setPoint(geometry_msgs::PointStamped point)
390 {
391 msg_.target_pos = point;
392 }
393
394private:
395 double max_yaw_vel_{}, max_pitch_vel_{}, track_timeout_{}, eject_sensitivity_ = 1.;
396 double time_constant_rc_{}, time_constant_pc_{};
397 bool eject_flag_{}, use_rc_{};
398};
399
400class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd>
401{
402public:
403 explicit ShooterCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::ShootCmd>(nh)
404 {
405 ros::NodeHandle limit_nh(nh, "heat_limit");
406 heat_limit_ = new HeatLimit(limit_nh);
407 nh.param("speed_10m_per_speed", speed_10_, 10.);
408 nh.param("speed_15m_per_speed", speed_15_, 15.);
409 nh.param("speed_16m_per_speed", speed_16_, 16.);
410 nh.param("speed_18m_per_speed", speed_18_, 18.);
411 nh.param("speed_30m_per_speed", speed_30_, 30.);
412 nh.getParam("wheel_speed_10", wheel_speed_10_);
413 nh.getParam("wheel_speed_15", wheel_speed_15_);
414 nh.getParam("wheel_speed_16", wheel_speed_16_);
415 nh.getParam("wheel_speed_18", wheel_speed_18_);
416 nh.getParam("wheel_speed_30", wheel_speed_30_);
417 nh.param("wheel_speed_offset_front", wheel_speed_offset_front_, 0.0);
418 nh.param("wheel_speed_offset_back", wheel_speed_offset_back_, 0.0);
419 nh.param("speed_oscillation", speed_oscillation_, 1.0);
420 nh.param("extra_wheel_speed_once", extra_wheel_speed_once_, 0.);
421 nh.param("deploy_wheel_speed", deploy_wheel_speed_, 410.0);
422 if (!nh.getParam("auto_wheel_speed", auto_wheel_speed_))
423 ROS_INFO("auto_wheel_speed no defined (namespace: %s), set to false.", nh.getNamespace().c_str());
424 if (!nh.getParam("target_acceleration_tolerance", target_acceleration_tolerance_))
425 {
426 target_acceleration_tolerance_ = 0.;
427 ROS_INFO("target_acceleration_tolerance no defined(namespace: %s), set to zero.", nh.getNamespace().c_str());
428 }
429 if (!nh.getParam("track_armor_error_tolerance", track_armor_error_tolerance_))
430 ROS_ERROR("track armor error tolerance no defined (namespace: %s)", nh.getNamespace().c_str());
431 nh.param("untrack_armor_error_tolerance", untrack_armor_error_tolerance_, track_armor_error_tolerance_);
432 nh.param("track_buff_error_tolerance", track_buff_error_tolerance_, track_armor_error_tolerance_);
433 if (!nh.getParam("max_track_target_vel", max_track_target_vel_))
434 {
435 max_track_target_vel_ = 9.0;
436 ROS_ERROR("max track target vel no defined (namespace: %s)", nh.getNamespace().c_str());
437 }
438 }
440 {
441 delete heat_limit_;
442 }
443
444 void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
445 {
447 }
448 void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
449 {
451 }
452 void updateRefereeStatus(bool status)
453 {
455 }
456 void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
457 {
458 gimbal_des_error_ = error;
459 }
460 void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
461 {
462 shoot_beforehand_cmd_ = data;
463 }
464 void updateTrackData(const rm_msgs::TrackData& data)
465 {
466 track_data_ = data;
467 }
468 void updateSuggestFireData(const std_msgs::Bool& data)
469 {
470 suggest_fire_ = data;
471 }
472 void updateShootData(const rm_msgs::ShootData& data)
473 {
474 shoot_data_ = data;
475 if (auto_wheel_speed_)
476 {
477 if (last_bullet_speed_ == 0.0)
478 last_bullet_speed_ = speed_des_;
479 if (shoot_data_.bullet_speed != last_bullet_speed_)
480 {
481 if (last_bullet_speed_ - speed_des_ >= speed_oscillation_ || shoot_data_.bullet_speed > speed_limit_)
482 {
483 total_extra_wheel_speed_ -= 5.0;
484 }
485 else if (speed_des_ - last_bullet_speed_ > speed_oscillation_)
486 {
487 total_extra_wheel_speed_ += 5.0;
488 }
489 }
490 if (shoot_data_.bullet_speed != 0.0)
491 last_bullet_speed_ = shoot_data_.bullet_speed;
492 }
493 }
494 void checkError(const ros::Time& time)
495 {
496 if (msg_.mode == rm_msgs::ShootCmd::PUSH && time - shoot_beforehand_cmd_.stamp < ros::Duration(0.1))
497 {
498 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT)
499 return;
500 if (shoot_beforehand_cmd_.cmd == rm_msgs::ShootBeforehandCmd::BAN_SHOOT)
501 {
502 setMode(rm_msgs::ShootCmd::READY);
503 return;
504 }
505 }
506 double gimbal_error_tolerance;
507 if (track_data_.id == 12)
508 gimbal_error_tolerance = track_buff_error_tolerance_;
509 else if (std::abs(track_data_.v_yaw) < max_track_target_vel_)
510 gimbal_error_tolerance = track_armor_error_tolerance_;
511 else
512 gimbal_error_tolerance = untrack_armor_error_tolerance_;
513 if (((gimbal_des_error_.error > gimbal_error_tolerance && time - gimbal_des_error_.stamp < ros::Duration(0.1)) ||
514 (track_data_.accel > target_acceleration_tolerance_)) ||
515 (!suggest_fire_.data && armor_type_ == rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE))
516 if (msg_.mode == rm_msgs::ShootCmd::PUSH)
517 {
518 setMode(rm_msgs::ShootCmd::READY);
519 }
520 }
521 void sendCommand(const ros::Time& time) override
522 {
523 msg_.wheel_speed = getWheelSpeedDes();
524 msg_.wheels_speed_offset_front = getFrontWheelSpeedOffset();
525 msg_.wheels_speed_offset_back = getBackWheelSpeedOffset();
528 }
529 double getSpeed()
530 {
532 return speed_des_;
533 }
535 {
537 if (hero_flag_)
538 {
539 if (deploy_flag_)
540 return deploy_wheel_speed_;
541 return wheel_speed_des_;
542 }
543 return wheel_speed_des_ + total_extra_wheel_speed_;
544 }
545 void setDeployState(bool flag)
546 {
547 deploy_flag_ = flag;
548 }
549 void setHeroState(bool flag)
550 {
551 hero_flag_ = flag;
552 }
554 {
555 return deploy_flag_;
556 }
558 {
559 switch (heat_limit_->getSpeedLimit())
560 {
561 case rm_msgs::ShootCmd::SPEED_10M_PER_SECOND:
562 {
563 speed_limit_ = 10.0;
564 speed_des_ = speed_10_;
565 wheel_speed_des_ = wheel_speed_10_;
566 break;
567 }
568 case rm_msgs::ShootCmd::SPEED_15M_PER_SECOND:
569 {
570 speed_limit_ = 15.0;
571 speed_des_ = speed_15_;
572 wheel_speed_des_ = wheel_speed_15_;
573 break;
574 }
575 case rm_msgs::ShootCmd::SPEED_16M_PER_SECOND:
576 {
577 speed_limit_ = 16.0;
578 speed_des_ = speed_16_;
579 wheel_speed_des_ = wheel_speed_16_;
580 break;
581 }
582 case rm_msgs::ShootCmd::SPEED_18M_PER_SECOND:
583 {
584 speed_limit_ = 18.0;
585 speed_des_ = speed_18_;
586 wheel_speed_des_ = wheel_speed_18_;
587 break;
588 }
589 case rm_msgs::ShootCmd::SPEED_30M_PER_SECOND:
590 {
591 speed_limit_ = 30.0;
592 speed_des_ = speed_30_;
593 wheel_speed_des_ = wheel_speed_30_;
594 break;
595 }
596 }
597 }
599 {
600 wheels_speed_offset_front_ = wheel_speed_offset_front_;
601 return wheels_speed_offset_front_;
602 }
604 {
605 wheels_speed_offset_back_ = wheel_speed_offset_back_;
606 return wheels_speed_offset_back_;
607 }
609 {
610 if (hero_flag_)
611 wheel_speed_offset_front_ -= extra_wheel_speed_once_;
612 else
613 total_extra_wheel_speed_ -= extra_wheel_speed_once_;
614 }
616 {
617 if (hero_flag_)
618 wheel_speed_offset_front_ += extra_wheel_speed_once_;
619 else
620 total_extra_wheel_speed_ += extra_wheel_speed_once_;
621 }
622 void setArmorType(uint8_t armor_type)
623 {
624 armor_type_ = armor_type;
625 }
626 void setShootFrequency(uint8_t mode)
627 {
629 }
631 {
633 }
634 void setZero() override{};
636
638 {
639 return msg_.mode;
640 }
641
642private:
643 double speed_10_{}, speed_15_{}, speed_16_{}, speed_18_{}, speed_30_{}, speed_des_{}, speed_limit_{};
644 double wheel_speed_10_{}, wheel_speed_15_{}, wheel_speed_16_{}, wheel_speed_18_{}, wheel_speed_30_{},
645 wheel_speed_des_{}, last_bullet_speed_{}, speed_oscillation_{};
646 double wheel_speed_offset_front_{}, wheel_speed_offset_back_{};
647 double wheels_speed_offset_front_{}, wheels_speed_offset_back_{};
648 double track_armor_error_tolerance_{};
649 double track_buff_error_tolerance_{};
650 double untrack_armor_error_tolerance_{};
651 double max_track_target_vel_{};
652 double target_acceleration_tolerance_{};
653 double extra_wheel_speed_once_{};
654 double total_extra_wheel_speed_{};
655 double deploy_wheel_speed_{};
656 bool auto_wheel_speed_ = false;
657 bool hero_flag_{};
658 bool deploy_flag_ = false;
659 rm_msgs::TrackData track_data_;
660 rm_msgs::GimbalDesError gimbal_des_error_;
661 rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
662 rm_msgs::ShootData shoot_data_;
663 std_msgs::Bool suggest_fire_;
664 uint8_t armor_type_{};
665};
666
667class UseLioCommandSender : public CommandSenderBase<std_msgs::Bool>
668{
669public:
670 explicit UseLioCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::Bool>(nh)
671 {
672 }
673
674 void setUseLio(bool flag)
675 {
676 msg_.data = flag;
677 }
678 bool getUseLio() const
679 {
680 return msg_.data;
681 }
682 void setZero() override{};
683};
684
685class BalanceCommandSender : public CommandSenderBase<std_msgs::UInt8>
686{
687public:
688 explicit BalanceCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::UInt8>(nh)
689 {
690 }
691
692 void setBalanceMode(const int mode)
693 {
694 msg_.data = mode;
695 }
697 {
698 return msg_.data;
699 }
700 void setZero() override{};
701};
702
703class LegCommandSender : public CommandSenderBase<rm_msgs::LegCmd>
704{
705public:
706 explicit LegCommandSender(ros::NodeHandle& nh) : CommandSenderBase<rm_msgs::LegCmd>(nh)
707 {
708 }
709
710 void setJump(bool jump)
711 {
712 msg_.jump = jump;
713 }
714 void setLgeLength(double length)
715 {
716 msg_.leg_length = length;
717 }
718 bool getJump()
719 {
720 return msg_.jump;
721 }
723 {
724 return msg_.leg_length;
725 }
726 void setZero() override{};
727};
728
729class Vel3DCommandSender : public HeaderStampCommandSenderBase<geometry_msgs::TwistStamped>
730{
731public:
732 explicit Vel3DCommandSender(ros::NodeHandle& nh) : HeaderStampCommandSenderBase(nh)
733 {
734 if (!nh.getParam("max_linear_x", max_linear_x_))
735 ROS_ERROR("Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
736 if (!nh.getParam("max_linear_y", max_linear_y_))
737 ROS_ERROR("Max Y linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
738 if (!nh.getParam("max_linear_z", max_linear_z_))
739 ROS_ERROR("Max Z linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
740 if (!nh.getParam("max_angular_x", max_angular_x_))
741 ROS_ERROR("Max X linear velocity no defined (namespace: %s)", nh.getNamespace().c_str());
742 if (!nh.getParam("max_angular_y", max_angular_y_))
743 ROS_ERROR("Max Y angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
744 if (!nh.getParam("max_angular_z", max_angular_z_))
745 ROS_ERROR("Max Z angular velocity no defined (namespace: %s)", nh.getNamespace().c_str());
746 }
747 void setLinearVel(double scale_x, double scale_y, double scale_z)
748 {
749 msg_.twist.linear.x = max_linear_x_ * scale_x;
750 msg_.twist.linear.y = max_linear_y_ * scale_y;
751 msg_.twist.linear.z = max_linear_z_ * scale_z;
752 }
753 void setAngularVel(double scale_x, double scale_y, double scale_z)
754 {
755 msg_.twist.angular.x = max_angular_x_ * scale_x;
756 msg_.twist.angular.y = max_angular_y_ * scale_y;
757 msg_.twist.angular.z = max_angular_z_ * scale_z;
758 }
759 void setZero() override
760 {
761 msg_.twist.linear.x = 0.;
762 msg_.twist.linear.y = 0.;
763 msg_.twist.linear.z = 0.;
764 msg_.twist.angular.x = 0.;
765 msg_.twist.angular.y = 0.;
766 msg_.twist.angular.z = 0.;
767 }
768
769private:
770 double max_linear_x_{}, max_linear_y_{}, max_linear_z_{}, max_angular_x_{}, max_angular_y_{}, max_angular_z_{};
771};
772
774{
775public:
776 explicit JointPositionBinaryCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::Float64>(nh)
777 {
778 ROS_ASSERT(nh.getParam("on_pos", on_pos_) && nh.getParam("off_pos", off_pos_));
779 }
780 void on()
781 {
782 msg_.data = on_pos_;
783 state = true;
784 }
785 void off()
786 {
787 msg_.data = off_pos_;
788 state = false;
789 }
790 void changePosition(double scale)
791 {
792 current_position_ = msg_.data;
793 change_position_ = current_position_ + scale * per_change_position_;
794 msg_.data = change_position_;
795 }
796 bool getState() const
797 {
798 return state;
799 }
800 void sendCommand(const ros::Time& time) override
801 {
803 }
804 void setZero() override{};
805
806private:
807 bool state{};
808 double on_pos_{}, off_pos_{}, current_position_{}, change_position_{}, per_change_position_{ 0.05 };
809};
810
811class CardCommandSender : public CommandSenderBase<std_msgs::Float64>
812{
813public:
814 explicit CardCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::Float64>(nh)
815 {
816 ROS_ASSERT(nh.getParam("long_pos", long_pos_) && nh.getParam("short_pos", short_pos_) &&
817 nh.getParam("off_pos", off_pos_));
818 }
819 void long_on()
820 {
821 msg_.data = long_pos_;
822 state = true;
823 }
824 void short_on()
825 {
826 msg_.data = short_pos_;
827 state = true;
828 }
829 void off()
830 {
831 msg_.data = off_pos_;
832 state = false;
833 }
834 bool getState() const
835 {
836 return state;
837 }
838 void sendCommand(const ros::Time& time) override
839 {
841 }
842 void setZero() override{};
843
844private:
845 bool state{};
846 double long_pos_{}, short_pos_{}, off_pos_{};
847};
848
849class JointJogCommandSender : public CommandSenderBase<std_msgs::Float64>
850{
851public:
852 explicit JointJogCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
853 : CommandSenderBase<std_msgs::Float64>(nh), joint_state_(joint_state)
854 {
855 ROS_ASSERT(nh.getParam("joint", joint_));
856 ROS_ASSERT(nh.getParam("step", step_));
857 }
858 void reset()
859 {
860 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
861 if (i != joint_state_.name.end())
862 msg_.data = joint_state_.position[std::distance(joint_state_.name.begin(), i)];
863 else
864 msg_.data = NAN;
865 }
866 void plus()
867 {
868 if (msg_.data != NAN)
869 {
870 msg_.data += step_;
871 sendCommand(ros::Time());
872 }
873 }
874 void minus()
875 {
876 if (msg_.data != NAN)
877 {
878 msg_.data -= step_;
879 sendCommand(ros::Time());
880 }
881 }
882 const std::string& getJoint()
883 {
884 return joint_;
885 }
886
887private:
888 std::string joint_{};
889 const sensor_msgs::JointState& joint_state_;
890 double step_{};
891};
892
893class JointPointCommandSender : public CommandSenderBase<std_msgs::Float64>
894{
895public:
896 explicit JointPointCommandSender(ros::NodeHandle& nh, const sensor_msgs::JointState& joint_state)
897 : CommandSenderBase<std_msgs::Float64>(nh), joint_state_(joint_state)
898 {
899 ROS_ASSERT(nh.getParam("joint", joint_));
900 }
901 void setPoint(double point)
902 {
903 msg_.data = point;
904 }
906 {
907 auto i = std::find(joint_state_.name.begin(), joint_state_.name.end(), joint_);
908 if (i != joint_state_.name.end())
909 {
910 index_ = std::distance(joint_state_.name.begin(), i);
911 return index_;
912 }
913 else
914 {
915 ROS_ERROR("Can not find joint %s", joint_.c_str());
916 return -1;
917 }
918 }
919 void setZero() override{};
920
921private:
922 std::string joint_{};
923 int index_{};
924 const sensor_msgs::JointState& joint_state_;
925};
926
927class CameraSwitchCommandSender : public CommandSenderBase<std_msgs::String>
928{
929public:
930 explicit CameraSwitchCommandSender(ros::NodeHandle& nh) : CommandSenderBase<std_msgs::String>(nh)
931 {
932 ROS_ASSERT(nh.getParam("camera_left_name", camera1_name_) && nh.getParam("camera_right_name", camera2_name_));
933 msg_.data = camera2_name_;
934 }
936 {
937 msg_.data = camera1_name_;
938 }
940 {
941 msg_.data = camera2_name_;
942 }
943 void sendCommand(const ros::Time& time) override
944 {
946 }
947 void setZero() override{};
948
949private:
950 std::string camera1_name_{}, camera2_name_{};
951};
952
953class MultiDofCommandSender : public TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>
954{
955public:
956 explicit MultiDofCommandSender(ros::NodeHandle& nh) : TimeStampCommandSenderBase<rm_msgs::MultiDofCmd>(nh)
957 {
958 }
960 void setMode(int mode)
961 {
962 msg_.mode = mode;
963 }
965 {
966 return msg_.mode;
967 }
968 void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y,
969 double angular_z)
970 {
971 msg_.linear.x = linear_x;
972 msg_.linear.y = linear_y;
973 msg_.linear.z = linear_z;
974 msg_.angular.x = angular_x;
975 msg_.angular.y = angular_y;
976 msg_.angular.z = angular_z;
977 }
978 void setZero() override
979 {
980 msg_.linear.x = 0;
981 msg_.linear.y = 0;
982 msg_.linear.z = 0;
983 msg_.angular.x = 0;
984 msg_.angular.y = 0;
985 msg_.angular.z = 0;
986 }
987
988private:
989 ros::Time time_;
990};
991
993{
994public:
995 DoubleBarrelCommandSender(ros::NodeHandle& nh)
996 {
997 ros::NodeHandle shooter_ID1_nh(nh, "shooter_ID1");
998 shooter_ID1_cmd_sender_ = new ShooterCommandSender(shooter_ID1_nh);
999 ros::NodeHandle shooter_ID2_nh(nh, "shooter_ID2");
1000 shooter_ID2_cmd_sender_ = new ShooterCommandSender(shooter_ID2_nh);
1001 ros::NodeHandle barrel_nh(nh, "barrel");
1002 barrel_command_sender_ = new rm_common::JointPointCommandSender(barrel_nh, joint_state_);
1003
1004 barrel_nh.getParam("is_double_barrel", is_double_barrel_);
1005 barrel_nh.getParam("id1_point", id1_point_);
1006 barrel_nh.getParam("id2_point", id2_point_);
1007 barrel_nh.getParam("frequency_threshold", frequency_threshold_);
1008 barrel_nh.getParam("check_launch_threshold", check_launch_threshold_);
1009 barrel_nh.getParam("check_switch_threshold", check_switch_threshold_);
1010 barrel_nh.getParam("ready_duration", ready_duration_);
1011 barrel_nh.getParam("switching_duration", switching_duration_);
1012
1013 joint_state_sub_ = nh.subscribe<sensor_msgs::JointState>("/joint_states", 10,
1014 &DoubleBarrelCommandSender::jointStateCallback, this);
1015 trigger_state_sub_ = nh.subscribe<control_msgs::JointControllerState>(
1016 "/controllers/shooter_controller/trigger/state", 10, &DoubleBarrelCommandSender::triggerStateCallback, this);
1017 }
1018
1019 void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
1020 {
1021 shooter_ID1_cmd_sender_->updateGameRobotStatus(data);
1022 shooter_ID2_cmd_sender_->updateGameRobotStatus(data);
1023 }
1024 void updatePowerHeatData(const rm_msgs::PowerHeatData data)
1025 {
1026 shooter_ID1_cmd_sender_->heat_limit_->setCoolingHeatOfShooter(data);
1027 shooter_ID2_cmd_sender_->heat_limit_->setCoolingHeatOfShooter(data);
1028 }
1029 void updateRefereeStatus(bool status)
1030 {
1031 shooter_ID1_cmd_sender_->updateRefereeStatus(status);
1032 shooter_ID2_cmd_sender_->updateRefereeStatus(status);
1033 }
1034 void updateGimbalDesError(const rm_msgs::GimbalDesError& error)
1035 {
1036 shooter_ID1_cmd_sender_->updateGimbalDesError(error);
1037 shooter_ID2_cmd_sender_->updateGimbalDesError(error);
1038 }
1039 void updateTrackData(const rm_msgs::TrackData& data)
1040 {
1041 shooter_ID1_cmd_sender_->updateTrackData(data);
1042 shooter_ID2_cmd_sender_->updateTrackData(data);
1043 }
1044 void updateSuggestFireData(const std_msgs::Bool& data)
1045 {
1046 shooter_ID1_cmd_sender_->updateSuggestFireData(data);
1047 shooter_ID2_cmd_sender_->updateSuggestFireData(data);
1048 }
1049 void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd& data)
1050 {
1051 shooter_ID1_cmd_sender_->updateShootBeforehandCmd(data);
1052 shooter_ID2_cmd_sender_->updateShootBeforehandCmd(data);
1053 }
1054
1055 void setMode(int mode)
1056 {
1057 getBarrel()->setMode(mode);
1058 }
1059 void setZero()
1060 {
1061 getBarrel()->setZero();
1062 }
1063 void checkError(const ros::Time& time)
1064 {
1065 getBarrel()->checkError(time);
1066 }
1067 void sendCommand(const ros::Time& time)
1068 {
1069 if (checkSwitch())
1070 need_switch_ = true;
1071 if (need_switch_)
1072 switchBarrel();
1073 checklaunch();
1074 if (getBarrel()->getMsg()->mode == rm_msgs::ShootCmd::PUSH)
1075 last_push_time_ = time;
1076 getBarrel()->sendCommand(time);
1077 }
1078 void init()
1079 {
1080 ros::Time time = ros::Time::now();
1081 barrel_command_sender_->setPoint(id1_point_);
1082 shooter_ID1_cmd_sender_->setMode(rm_msgs::ShootCmd::STOP);
1083 shooter_ID2_cmd_sender_->setMode(rm_msgs::ShootCmd::STOP);
1084 barrel_command_sender_->sendCommand(time);
1085 shooter_ID1_cmd_sender_->sendCommand(time);
1086 shooter_ID2_cmd_sender_->sendCommand(time);
1087 }
1088 void setArmorType(uint8_t armor_type)
1089 {
1090 shooter_ID1_cmd_sender_->setArmorType(armor_type);
1091 shooter_ID2_cmd_sender_->setArmorType(armor_type);
1092 }
1093 void setShootFrequency(uint8_t mode)
1094 {
1095 getBarrel()->setShootFrequency(mode);
1096 }
1098 {
1099 return getBarrel()->getShootFrequency();
1100 }
1101 double getSpeed()
1102 {
1103 return getBarrel()->getSpeed();
1104 }
1105
1106private:
1107 ShooterCommandSender* getBarrel()
1108 {
1109 if (barrel_command_sender_->getMsg()->data == id1_point_)
1110 is_id1_ = true;
1111 else
1112 is_id1_ = false;
1113 return is_id1_ ? shooter_ID1_cmd_sender_ : shooter_ID2_cmd_sender_;
1114 }
1115 void switchBarrel()
1116 {
1117 ros::Time time = ros::Time::now();
1118 bool time_to_switch = (std::fmod(std::abs(trigger_error_), 2. * M_PI) < check_switch_threshold_);
1119 setMode(rm_msgs::ShootCmd::READY);
1120 if (time_to_switch || (time - last_push_time_).toSec() > ready_duration_)
1121 {
1122 barrel_command_sender_->getMsg()->data == id2_point_ ? barrel_command_sender_->setPoint(id1_point_) :
1123 barrel_command_sender_->setPoint(id2_point_);
1124 barrel_command_sender_->sendCommand(time);
1125 last_switch_time_ = time;
1126 need_switch_ = false;
1127 is_switching_ = true;
1128 }
1129 }
1130
1131 void checklaunch()
1132 {
1133 ros::Time time = ros::Time::now();
1134 if (is_switching_)
1135 {
1136 setMode(rm_msgs::ShootCmd::READY);
1137 if ((time - last_switch_time_).toSec() > switching_duration_ ||
1138 (std::abs(joint_state_.position[barrel_command_sender_->getIndex()] -
1139 barrel_command_sender_->getMsg()->data) < check_launch_threshold_))
1140 is_switching_ = false;
1141 }
1142 }
1143
1144 bool checkSwitch()
1145 {
1146 if (!is_double_barrel_)
1147 return false;
1148 if (shooter_ID1_cmd_sender_->heat_limit_->getCoolingLimit() == 0 ||
1149 shooter_ID2_cmd_sender_->heat_limit_->getCoolingLimit() == 0)
1150 {
1151 ROS_WARN_ONCE("Can not get cooling limit");
1152 return false;
1153 }
1154 if (shooter_ID1_cmd_sender_->heat_limit_->getShootFrequency() < frequency_threshold_ ||
1155 shooter_ID2_cmd_sender_->heat_limit_->getShootFrequency() < frequency_threshold_)
1156 {
1157 if (getBarrel() == shooter_ID1_cmd_sender_)
1158 return getBarrel()->heat_limit_->getShootFrequency() < frequency_threshold_ &&
1159 shooter_ID2_cmd_sender_->heat_limit_->getShootFrequency() > frequency_threshold_;
1160 else
1161 return getBarrel()->heat_limit_->getShootFrequency() < frequency_threshold_ &&
1162 shooter_ID1_cmd_sender_->heat_limit_->getShootFrequency() > frequency_threshold_;
1163 }
1164 else
1165 return false;
1166 }
1167 void triggerStateCallback(const control_msgs::JointControllerState::ConstPtr& data)
1168 {
1169 trigger_error_ = data->error;
1170 }
1171 void jointStateCallback(const sensor_msgs::JointState::ConstPtr& data)
1172 {
1173 joint_state_ = *data;
1174 }
1175 ShooterCommandSender* shooter_ID1_cmd_sender_;
1176 ShooterCommandSender* shooter_ID2_cmd_sender_;
1177 JointPointCommandSender* barrel_command_sender_{};
1178 ros::Subscriber trigger_state_sub_;
1179 ros::Subscriber joint_state_sub_;
1180 sensor_msgs::JointState joint_state_;
1181 bool is_double_barrel_{ false }, need_switch_{ false }, is_switching_{ false };
1182 ros::Time last_switch_time_, last_push_time_;
1183 double ready_duration_, switching_duration_;
1184 double trigger_error_;
1185 bool is_id1_{ false };
1186 double id1_point_, id2_point_;
1187 double frequency_threshold_;
1188 double check_launch_threshold_, check_switch_threshold_;
1189};
1190
1191} // namespace rm_common
Definition command_sender.h:686
BalanceCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:688
int getBalanceMode()
Definition command_sender.h:696
void setZero() override
Definition command_sender.h:700
void setBalanceMode(const int mode)
Definition command_sender.h:692
Definition command_sender.h:928
CameraSwitchCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:930
void setZero() override
Definition command_sender.h:947
void switchCameraRight()
Definition command_sender.h:939
void switchCameraLeft()
Definition command_sender.h:935
void sendCommand(const ros::Time &time) override
Definition command_sender.h:943
Definition command_sender.h:812
void long_on()
Definition command_sender.h:819
void off()
Definition command_sender.h:829
void sendCommand(const ros::Time &time) override
Definition command_sender.h:838
void setZero() override
Definition command_sender.h:842
CardCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:814
bool getState() const
Definition command_sender.h:834
void short_on()
Definition command_sender.h:824
void setZero() override
Definition command_sender.h:315
ChassisActiveSuspensionCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:311
Definition command_sender.h:245
void setFollowVelDes(double follow_vel_des)
Definition command_sender.h:285
void updateRefereeStatus(bool status)
Definition command_sender.h:281
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:269
void sendChassisCommand(const ros::Time &time, bool is_gyro)
Definition command_sender.h:293
void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data) override
Definition command_sender.h:277
ChassisCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:247
PowerLimit * power_limit_
Definition command_sender.h:302
void setZero() override
Definition command_sender.h:301
void setWirelessState(bool state)
Definition command_sender.h:289
void updateSafetyPower(int safety_power)
Definition command_sender.h:265
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:273
Definition command_sender.h:92
virtual void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:110
virtual void sendCommand(const ros::Time &time)
Definition command_sender.h:106
virtual void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:119
void setMode(int mode)
Definition command_sender.h:101
ros::Publisher pub_
Definition command_sender.h:131
uint32_t queue_size_
Definition command_sender.h:130
MsgType msg_
Definition command_sender.h:132
MsgType * getMsg()
Definition command_sender.h:123
CommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:94
std::string topic_
Definition command_sender.h:129
virtual void updateGameStatus(const rm_msgs::GameStatus data)
Definition command_sender.h:113
virtual void updateCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition command_sender.h:116
Definition command_sender.h:993
void setZero()
Definition command_sender.h:1059
DoubleBarrelCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:995
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:1039
double getSpeed()
Definition command_sender.h:1101
void setMode(int mode)
Definition command_sender.h:1055
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:1044
void sendCommand(const ros::Time &time)
Definition command_sender.h:1067
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:1034
void init()
Definition command_sender.h:1078
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:1049
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data)
Definition command_sender.h:1019
void updateRefereeStatus(bool status)
Definition command_sender.h:1029
void setShootFrequency(uint8_t mode)
Definition command_sender.h:1093
void setArmorType(uint8_t armor_type)
Definition command_sender.h:1088
void updatePowerHeatData(const rm_msgs::PowerHeatData data)
Definition command_sender.h:1024
uint8_t getShootFrequency()
Definition command_sender.h:1097
void checkError(const ros::Time &time)
Definition command_sender.h:1063
Definition command_sender.h:321
void setRate(double scale_yaw, double scale_pitch)
Definition command_sender.h:339
bool getEject() const
Definition command_sender.h:385
void setUseRc(bool flag)
Definition command_sender.h:381
void setBulletSpeed(double bullet_speed)
Definition command_sender.h:373
void setPoint(geometry_msgs::PointStamped point)
Definition command_sender.h:389
void setTrajFrameId(const std::string &traj_frame_id)
Definition command_sender.h:364
void setGimbalTraj(double traj_yaw, double traj_pitch)
Definition command_sender.h:359
void setEject(bool flag)
Definition command_sender.h:377
void setZero() override
Definition command_sender.h:368
GimbalCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:323
Definition command_sender.h:151
HeaderStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:153
void sendCommand(const ros::Time &time) override
Definition command_sender.h:156
Definition heat_limit.h:52
int getCoolingLimit()
Definition heat_limit.h:178
double getShootFrequency() const
Definition heat_limit.h:147
void setStatusOfShooter(const rm_msgs::GameRobotStatus data)
Definition heat_limit.h:119
void setRefereeStatus(bool status)
Definition heat_limit.h:142
void setShootFrequency(uint8_t mode)
Definition heat_limit.h:188
void setCoolingHeatOfShooter(const rm_msgs::PowerHeatData data)
Definition heat_limit.h:125
int getSpeedLimit()
Definition heat_limit.h:166
bool getShootFrequencyMode() const
Definition heat_limit.h:193
Definition command_sender.h:850
void reset()
Definition command_sender.h:858
const std::string & getJoint()
Definition command_sender.h:882
JointJogCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:852
void minus()
Definition command_sender.h:874
void plus()
Definition command_sender.h:866
Definition command_sender.h:894
int getIndex()
Definition command_sender.h:905
void setZero() override
Definition command_sender.h:919
JointPointCommandSender(ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
Definition command_sender.h:896
void setPoint(double point)
Definition command_sender.h:901
Definition command_sender.h:774
JointPositionBinaryCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:776
void sendCommand(const ros::Time &time) override
Definition command_sender.h:800
void setZero() override
Definition command_sender.h:804
bool getState() const
Definition command_sender.h:796
void changePosition(double scale)
Definition command_sender.h:790
void off()
Definition command_sender.h:785
void on()
Definition command_sender.h:780
Definition command_sender.h:704
void setZero() override
Definition command_sender.h:726
LegCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:706
void setLgeLength(double length)
Definition command_sender.h:714
bool getJump()
Definition command_sender.h:718
double getLgeLength()
Definition command_sender.h:722
void setJump(bool jump)
Definition command_sender.h:710
Definition linear_interpolation.h:12
double output(double input)
Definition linear_interpolation.h:37
void init(XmlRpc::XmlRpcValue &config)
Definition linear_interpolation.h:15
Definition command_sender.h:954
void setGroupValue(double linear_x, double linear_y, double linear_z, double angular_x, double angular_y, double angular_z)
Definition command_sender.h:968
MultiDofCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:956
int getMode()
Definition command_sender.h:964
void setZero() override
Definition command_sender.h:978
void setMode(int mode)
Definition command_sender.h:960
Definition power_limit.h:53
void setRefereeStatus(bool status)
Definition power_limit.h:131
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
Definition power_limit.h:125
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
Definition power_limit.h:120
void setGameRobotData(const rm_msgs::GameRobotStatus data)
Definition power_limit.h:115
void setLimitPower(rm_msgs::ChassisCmd &chassis_cmd, bool is_gyro)
Definition power_limit.h:176
void updateSafetyPower(int safety_power)
Definition power_limit.h:98
Definition command_sender.h:401
void setShootFrequency(uint8_t mode)
Definition command_sender.h:626
void updateSuggestFireData(const std_msgs::Bool &data)
Definition command_sender.h:468
void setZero() override
Definition command_sender.h:634
void updatePowerHeatData(const rm_msgs::PowerHeatData data) override
Definition command_sender.h:448
void sendCommand(const ros::Time &time) override
Definition command_sender.h:521
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:464
void setSpeedDesAndWheelSpeedDes()
Definition command_sender.h:557
uint8_t getShootFrequency()
Definition command_sender.h:630
void setDeployState(bool flag)
Definition command_sender.h:545
void setHeroState(bool flag)
Definition command_sender.h:549
void dropSpeed()
Definition command_sender.h:608
int getShootMode()
Definition command_sender.h:637
double getBackWheelSpeedOffset()
Definition command_sender.h:603
void updateRefereeStatus(bool status)
Definition command_sender.h:452
ShooterCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:403
double getFrontWheelSpeedOffset()
Definition command_sender.h:598
double getWheelSpeedDes()
Definition command_sender.h:534
~ShooterCommandSender()
Definition command_sender.h:439
void raiseSpeed()
Definition command_sender.h:615
void updateGameRobotStatus(const rm_msgs::GameRobotStatus data) override
Definition command_sender.h:444
void updateShootData(const rm_msgs::ShootData &data)
Definition command_sender.h:472
void setArmorType(uint8_t armor_type)
Definition command_sender.h:622
double getSpeed()
Definition command_sender.h:529
void checkError(const ros::Time &time)
Definition command_sender.h:494
HeatLimit * heat_limit_
Definition command_sender.h:635
void updateGimbalDesError(const rm_msgs::GimbalDesError &error)
Definition command_sender.h:456
void updateShootBeforehandCmd(const rm_msgs::ShootBeforehandCmd &data)
Definition command_sender.h:460
bool getDeployState()
Definition command_sender.h:553
Definition command_sender.h:137
void sendCommand(const ros::Time &time) override
Definition command_sender.h:142
TimeStampCommandSenderBase(ros::NodeHandle &nh)
Definition command_sender.h:139
Definition command_sender.h:668
void setUseLio(bool flag)
Definition command_sender.h:674
void setZero() override
Definition command_sender.h:682
bool getUseLio() const
Definition command_sender.h:678
UseLioCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:670
Definition command_sender.h:164
ros::Subscriber chassis_power_limit_subscriber_
Definition command_sender.h:240
void updateTrackData(const rm_msgs::TrackData &data)
Definition command_sender.h:188
void chassisCmdCallback(const rm_msgs::ChassisCmd::ConstPtr &msg)
Definition command_sender.h:231
void setAngularZVel(double scale, double limit)
Definition command_sender.h:208
void setLinearYVel(double scale)
Definition command_sender.h:196
void setAngularZVel(double scale)
Definition command_sender.h:200
void setLinearXVel(double scale)
Definition command_sender.h:192
void set2DVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:217
double target_vel_yaw_threshold_
Definition command_sender.h:238
rm_msgs::TrackData track_data_
Definition command_sender.h:241
LinearInterp max_linear_x_
Definition command_sender.h:236
LinearInterp max_linear_y_
Definition command_sender.h:236
double vel_direction_
Definition command_sender.h:239
LinearInterp max_angular_z_
Definition command_sender.h:236
double power_limit_
Definition command_sender.h:237
void setZero() override
Definition command_sender.h:223
Vel2DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:166
Definition command_sender.h:730
void setZero() override
Definition command_sender.h:759
Vel3DCommandSender(ros::NodeHandle &nh)
Definition command_sender.h:732
void setAngularVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:753
void setLinearVel(double scale_x, double scale_y, double scale_z)
Definition command_sender.h:747
auto setTrajFrameIdIfSupported(TMsg &msg, const std::string &traj_frame_id, int) -> decltype((void)(msg.traj_frame_id=traj_frame_id), void())
Definition command_sender.h:78
Definition calibration_queue.h:44
T getParam(ros::NodeHandle &pnh, const std::string &param_name, const T &default_val)
Definition ros_utilities.h:44