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