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