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