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