From c85d94800bd1f344fb19d866410f74892758655c Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Tue, 28 May 2024 21:11:35 +0800 Subject: [PATCH 01/31] Add one judgement for rPress. --- src/chassis_gimbal_shooter_manual.cpp | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 2fcffb68..42a39541 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -414,17 +414,20 @@ void ChassisGimbalShooterManual::bRelease() void ChassisGimbalShooterManual::rPress() { - if (camera_switch_cmd_sender_) - camera_switch_cmd_sender_->switchCamera(); - if (scope_cmd_sender_) + if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_HERO || robot_id_ == rm_msgs::GameRobotStatus::RED_HERO) { - use_scope_ = !scope_cmd_sender_->getState(); - if (use_scope_) - gimbal_cmd_sender_->setEject(true); - else + if (camera_switch_cmd_sender_) + camera_switch_cmd_sender_->switchCamera(); + if (scope_cmd_sender_) { - gimbal_cmd_sender_->setEject(false); - adjust_image_transmission_ = false; + use_scope_ = !scope_cmd_sender_->getState(); + if (use_scope_) + gimbal_cmd_sender_->setEject(true); + else + { + gimbal_cmd_sender_->setEject(false); + adjust_image_transmission_ = false; + } } } } From e6ea89705d51dec1e6fb39974f98d8da9ab6523b Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Wed, 29 May 2024 18:00:20 +0800 Subject: [PATCH 02/31] Slow down the shooter's frequency when shooting buff. --- include/rm_manual/chassis_gimbal_shooter_manual.h | 4 +++- src/chassis_gimbal_shooter_manual.cpp | 9 +++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_manual.h b/include/rm_manual/chassis_gimbal_shooter_manual.h index bd147d4b..cd972128 100644 --- a/include/rm_manual/chassis_gimbal_shooter_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_manual.h @@ -52,6 +52,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual void suggestFireCallback(const std_msgs::Bool::ConstPtr& data) override; void trackCallback(const rm_msgs::TrackData::ConstPtr& data) override; void leftSwitchUpOn(ros::Duration duration); + void leftSwitchUpFall(); void mouseLeftPress(); void mouseLeftRelease() { @@ -85,10 +86,10 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual virtual void cPress(); virtual void bPress(); virtual void bRelease(); - virtual void rPress(); virtual void xReleasing(); virtual void shiftPress(); virtual void shiftRelease(); + void rPress(); void qPress() { shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::BURST); @@ -119,6 +120,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual rm_common::CalibrationQueue* gimbal_calibration_; geometry_msgs::PointStamped point_out_; + uint8_t last_shoot_freq_{}; bool prepare_shoot_ = false, turn_flag_ = false, is_balance_ = false, use_scope_ = false, adjust_image_transmission_ = false; diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 42a39541..b96b4f3e 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -40,6 +40,7 @@ ChassisGimbalShooterManual::ChassisGimbalShooterManual(ros::NodeHandle& nh, ros: self_inspection_event_.setRising(boost::bind(&ChassisGimbalShooterManual::selfInspectionStart, this)); game_start_event_.setRising(boost::bind(&ChassisGimbalShooterManual::gameStart, this)); left_switch_up_event_.setActiveHigh(boost::bind(&ChassisGimbalShooterManual::leftSwitchUpOn, this, _1)); + left_switch_up_event_.setFalling(boost::bind(&ChassisGimbalShooterManual::leftSwitchUpFall, this)); left_switch_mid_event_.setActiveHigh(boost::bind(&ChassisGimbalShooterManual::leftSwitchMidOn, this, _1)); e_event_.setEdge(boost::bind(&ChassisGimbalShooterManual::ePress, this), boost::bind(&ChassisGimbalShooterManual::eRelease, this)); @@ -313,6 +314,12 @@ void ChassisGimbalShooterManual::leftSwitchUpRise() { ChassisGimbalManual::leftSwitchUpRise(); gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::TRACK); + last_shoot_freq_ = shooter_cmd_sender_->getShootFrequency(); +} + +void ChassisGimbalShooterManual::leftSwitchUpFall() +{ + shooter_cmd_sender_->setShootFrequency(last_shoot_freq_); } void ChassisGimbalShooterManual::leftSwitchUpOn(ros::Duration duration) @@ -323,11 +330,13 @@ void ChassisGimbalShooterManual::leftSwitchUpOn(ros::Duration duration) gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::TRACK); if (duration > ros::Duration(1.)) { + shooter_cmd_sender_->setShootFrequency(last_shoot_freq_); shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::PUSH); shooter_cmd_sender_->checkError(ros::Time::now()); } else if (duration < ros::Duration(0.02)) { + shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::MINIMAL); shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::PUSH); shooter_cmd_sender_->checkError(ros::Time::now()); } From de4241dce37c61da638a6c57af9e30fa8896dea8 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Thu, 30 May 2024 16:39:06 +0800 Subject: [PATCH 03/31] Replace zPress to zPressing for slowing down shooter's frequency,slow down the shooter's frequency and gyro's speed when shooting buff. --- .../chassis_gimbal_shooter_cover_manual.h | 12 +- src/chassis_gimbal_shooter_cover_manual.cpp | 141 +++++++++++++++--- 2 files changed, 131 insertions(+), 22 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index c7474c5a..887f69ee 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -27,12 +27,19 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void rightSwitchDownRise() override; void rightSwitchMidRise() override; void rightSwitchUpRise() override; - void rPress() override; void ePress() override; - void zPressing(); + void cPress() override; + void zPress(); void zRelease(); void wPress() override; void wPressing() override; + void aPressing() override; + void sPressing() override; + void dPressing() override; + void wRelease() override; + void aRelease() override; + void sRelease() override; + void dRelease() override; virtual void ctrlZPress(); virtual void ctrlZRelease() @@ -41,6 +48,7 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual }; double low_speed_scale_{}, normal_speed_scale_{}; double exit_buff_mode_duration_{}; + double buff_gyro_rotate_limit_{}; rm_common::SwitchDetectionCaller* switch_buff_srv_{}; rm_common::SwitchDetectionCaller* switch_buff_type_srv_{}; rm_common::SwitchDetectionCaller* switch_exposure_srv_{}; diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 0006949c..118f518a 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -22,11 +22,12 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); + nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 6.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); - z_event_.setActiveHigh(boost::bind(&ChassisGimbalShooterCoverManual::zPressing, this)); - z_event_.setFalling(boost::bind(&ChassisGimbalShooterCoverManual::zRelease, this)); + z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::zPress, this), + boost::bind(&ChassisGimbalShooterCoverManual::zRelease, this)); } void ChassisGimbalShooterCoverManual::changeSpeedMode(SpeedMode speed_mode) @@ -132,21 +133,6 @@ void ChassisGimbalShooterCoverManual::rightSwitchUpRise() supply_ = false; } -void ChassisGimbalShooterCoverManual::rPress() -{ - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - { - chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::CHARGE); - if (switch_buff_type_srv_->getTarget() == rm_msgs::StatusChangeRequest::SMALL_BUFF) - switch_buff_type_srv_->setTargetType(rm_msgs::StatusChangeRequest::BIG_BUFF); - else - switch_buff_type_srv_->setTargetType(rm_msgs::StatusChangeRequest::SMALL_BUFF); - switch_buff_type_srv_->callService(); - } - else - chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL); -} - void ChassisGimbalShooterCoverManual::ePress() { switch_buff_srv_->switchTargetType(); @@ -157,16 +143,64 @@ void ChassisGimbalShooterCoverManual::ePress() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); + if (is_gyro_) + { + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + { + if (x_scale_ != 0.0 || y_scale_ != 0.0) + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); + else + vel_cmd_sender_->setAngularZVel(1.0); + } + else + { + if (x_scale_ != 0.0 || y_scale_ != 0.0) + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); + else + vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); + } + } +} + +void ChassisGimbalShooterCoverManual::cPress() +{ + if (is_gyro_) + { + chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::FOLLOW); + vel_cmd_sender_->setAngularZVel(0.0); + is_gyro_ = false; + } + else + { + chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::RAW); + is_gyro_ = true; + chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL); + if (x_scale_ != 0.0 || y_scale_ != 0.0) + { + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::SMALL_BUFF) + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); + else + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); + } + else + { + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::SMALL_BUFF) + vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); + else + vel_cmd_sender_->setAngularZVel(1.0); + } + } } -void ChassisGimbalShooterCoverManual::zPressing() +void ChassisGimbalShooterCoverManual::zPress() { + last_shoot_freq_ = shooter_cmd_sender_->getShootFrequency(); shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::MINIMAL); } void ChassisGimbalShooterCoverManual::zRelease() { - shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::LOW); + shooter_cmd_sender_->setShootFrequency(last_shoot_freq_); } void ChassisGimbalShooterCoverManual::wPress() @@ -191,6 +225,73 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); } + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::aPressing() +{ + ChassisGimbalShooterManual::aPressing(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::sPressing() +{ + ChassisGimbalShooterManual::sPressing(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::dPressing() +{ + ChassisGimbalShooterManual::dPressing(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::wRelease() +{ + ChassisGimbalShooterManual::wRelease(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::aRelease() +{ + ChassisGimbalShooterManual::aRelease(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::sRelease() +{ + ChassisGimbalShooterManual::sRelease(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::dRelease() +{ + ChassisGimbalShooterManual::dRelease(); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::ctrlZPress() @@ -210,4 +311,4 @@ void ChassisGimbalShooterCoverManual::ctrlZPress() } } -} // namespace rm_manual +} // namespace rm_manual \ No newline at end of file From 0c9a8afcbec7dc88bd861da3afdbe53e53201b71 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Thu, 30 May 2024 17:24:45 +0800 Subject: [PATCH 04/31] Modify something wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 118f518a..767513d2 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -311,4 +311,4 @@ void ChassisGimbalShooterCoverManual::ctrlZPress() } } -} // namespace rm_manual \ No newline at end of file +} // namespace rm_manual From 8cb89e146ec1d3e72aa5fd50017ea3399a309c33 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Mon, 8 Jul 2024 22:54:10 +0800 Subject: [PATCH 05/31] Modify the code for cleanliness. --- .../chassis_gimbal_shooter_cover_manual.h | 2 + src/chassis_gimbal_shooter_cover_manual.cpp | 56 ++++++++----------- 2 files changed, 26 insertions(+), 32 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index 887f69ee..13b619df 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -40,6 +40,8 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void aRelease() override; void sRelease() override; void dRelease() override; + void setAngularVelByTargetWhenMov(); + void setAngularVelByTargetWhenStopMov(); virtual void ctrlZPress(); virtual void ctrlZRelease() diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 767513d2..467fa8c5 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -225,73 +225,49 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); } - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenMov(); } void ChassisGimbalShooterCoverManual::aPressing() { ChassisGimbalShooterManual::aPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenMov(); } void ChassisGimbalShooterCoverManual::sPressing() { ChassisGimbalShooterManual::sPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenMov(); } void ChassisGimbalShooterCoverManual::dPressing() { ChassisGimbalShooterManual::dPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenMov(); } void ChassisGimbalShooterCoverManual::wRelease() { ChassisGimbalShooterManual::wRelease(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenStopMov(); } void ChassisGimbalShooterCoverManual::aRelease() { ChassisGimbalShooterManual::aRelease(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenStopMov(); } void ChassisGimbalShooterCoverManual::sRelease() { ChassisGimbalShooterManual::sRelease(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenStopMov(); } void ChassisGimbalShooterCoverManual::dRelease() { ChassisGimbalShooterManual::dRelease(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + setAngularVelByTargetWhenStopMov(); } void ChassisGimbalShooterCoverManual::ctrlZPress() @@ -311,4 +287,20 @@ void ChassisGimbalShooterCoverManual::ctrlZPress() } } +void ChassisGimbalShooterCoverManual::setAngularVelByTargetWhenMov() +{ + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::setAngularVelByTargetWhenStopMov() +{ + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + else + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +} + } // namespace rm_manual From d8220ef585065bf8cea68806a2ef8d7b3453a56d Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Thu, 1 Aug 2024 15:51:22 +0800 Subject: [PATCH 06/31] Fix wrong from merge. --- include/rm_manual/chassis_gimbal_shooter_manual.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_manual.h b/include/rm_manual/chassis_gimbal_shooter_manual.h index 11355e87..c9ce2e1d 100644 --- a/include/rm_manual/chassis_gimbal_shooter_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_manual.h @@ -88,7 +88,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual virtual void cPress(); virtual void bPress(); virtual void bRelease(); - virtual void xReleasing(); + virtual void xRelease(); virtual void shiftPress(); virtual void shiftRelease(); void rPress(); From 3b8b33d21833e563035967c6cfa263e6f604485d Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Thu, 1 Aug 2024 15:55:46 +0800 Subject: [PATCH 07/31] Delete something unused. --- src/chassis_gimbal_shooter_manual.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 126afc1c..6e28e1be 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -427,8 +427,6 @@ void ChassisGimbalShooterManual::rPress() { if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_HERO || robot_id_ == rm_msgs::GameRobotStatus::RED_HERO) { - if (camera_switch_cmd_sender_) - camera_switch_cmd_sender_->switchCamera(); if (scope_cmd_sender_) { use_scope_ = !scope_cmd_sender_->getState(); From fe64e3d7bc7ea0f00f815e6c0b6c85fab69d825d Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sat, 3 Aug 2024 12:17:05 +0800 Subject: [PATCH 08/31] Slow gyro's speed when shoot buff through wasdPress. --- .../chassis_gimbal_shooter_cover_manual.h | 12 +-- src/chassis_gimbal_shooter_cover_manual.cpp | 83 ++++++------------- 2 files changed, 27 insertions(+), 68 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index b8501291..79e3f29f 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -34,16 +34,10 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void ctrlRPressing(); void ctrlRRelease() override; void wPress() override; + void aPress() override; + void sPress() override; + void dPress() override; void wPressing() override; - void aPressing() override; - void sPressing() override; - void dPressing() override; - void wRelease() override; - void aRelease() override; - void sRelease() override; - void dRelease() override; - void setAngularVelByTargetWhenMov(); - void setAngularVelByTargetWhenStopMov(); virtual void ctrlZPress(); virtual void ctrlZRelease() diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index e7955412..d9949808 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -208,7 +208,31 @@ void ChassisGimbalShooterCoverManual::wPress() { ChassisGimbalShooterManual::wPress(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + { last_switch_time_ = ros::Time::now(); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + } +} + +void ChassisGimbalShooterCoverManual::aPress() +{ + ChassisGimbalShooterManual::aPress(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::sPress() +{ + ChassisGimbalShooterManual::sPress(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::dPress() +{ + ChassisGimbalShooterManual::dPress(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::wPressing() @@ -226,49 +250,6 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); } - setAngularVelByTargetWhenMov(); -} - -void ChassisGimbalShooterCoverManual::aPressing() -{ - ChassisGimbalShooterManual::aPressing(); - setAngularVelByTargetWhenMov(); -} - -void ChassisGimbalShooterCoverManual::sPressing() -{ - ChassisGimbalShooterManual::sPressing(); - setAngularVelByTargetWhenMov(); -} - -void ChassisGimbalShooterCoverManual::dPressing() -{ - ChassisGimbalShooterManual::dPressing(); - setAngularVelByTargetWhenMov(); -} - -void ChassisGimbalShooterCoverManual::wRelease() -{ - ChassisGimbalShooterManual::wRelease(); - setAngularVelByTargetWhenStopMov(); -} - -void ChassisGimbalShooterCoverManual::aRelease() -{ - ChassisGimbalShooterManual::aRelease(); - setAngularVelByTargetWhenStopMov(); -} - -void ChassisGimbalShooterCoverManual::sRelease() -{ - ChassisGimbalShooterManual::sRelease(); - setAngularVelByTargetWhenStopMov(); -} - -void ChassisGimbalShooterCoverManual::dRelease() -{ - ChassisGimbalShooterManual::dRelease(); - setAngularVelByTargetWhenStopMov(); } void ChassisGimbalShooterCoverManual::ctrlZPress() @@ -319,20 +300,4 @@ void ChassisGimbalShooterCoverManual::ctrlRRelease() shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::READY); } -void ChassisGimbalShooterCoverManual::setAngularVelByTargetWhenMov() -{ - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); -} - -void ChassisGimbalShooterCoverManual::setAngularVelByTargetWhenStopMov() -{ - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); - else - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); -} - } // namespace rm_manual From 930eedc22e8f4b5741ab183c02f69c1b1d4c61ae Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sat, 3 Aug 2024 12:20:21 +0800 Subject: [PATCH 09/31] Fix wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index d9949808..c6534443 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -207,7 +207,7 @@ void ChassisGimbalShooterCoverManual::zRelease() void ChassisGimbalShooterCoverManual::wPress() { ChassisGimbalShooterManual::wPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) { last_switch_time_ = ros::Time::now(); vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); @@ -217,21 +217,21 @@ void ChassisGimbalShooterCoverManual::wPress() void ChassisGimbalShooterCoverManual::aPress() { ChassisGimbalShooterManual::aPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::sPress() { ChassisGimbalShooterManual::sPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::dPress() { ChassisGimbalShooterManual::dPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } From 89c2464f92d9a3cb43039c5a1a073ab373f713b5 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 13:27:28 +0800 Subject: [PATCH 10/31] Fix wrong. --- .../chassis_gimbal_shooter_cover_manual.h | 6 +-- src/chassis_gimbal_shooter_cover_manual.cpp | 47 +++++++++---------- 2 files changed, 26 insertions(+), 27 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index 79e3f29f..defce76b 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -34,10 +34,10 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void ctrlRPressing(); void ctrlRRelease() override; void wPress() override; - void aPress() override; - void sPress() override; - void dPress() override; void wPressing() override; + void aPressing() override; + void sPressing() override; + void dPressing() override; virtual void ctrlZPress(); virtual void ctrlZRelease() diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index c6534443..16afc88d 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -208,31 +208,7 @@ void ChassisGimbalShooterCoverManual::wPress() { ChassisGimbalShooterManual::wPress(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - { last_switch_time_ = ros::Time::now(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); - } -} - -void ChassisGimbalShooterCoverManual::aPress() -{ - ChassisGimbalShooterManual::aPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); -} - -void ChassisGimbalShooterCoverManual::sPress() -{ - ChassisGimbalShooterManual::sPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); -} - -void ChassisGimbalShooterCoverManual::dPress() -{ - ChassisGimbalShooterManual::dPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::wPressing() @@ -249,9 +225,32 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } } +void ChassisGimbalShooterCoverManual::aPressing() +{ + ChassisGimbalShooterManual::aPressing(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::sPressing() +{ + ChassisGimbalShooterManual::sPressing(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::dPressing() +{ + ChassisGimbalShooterManual::dPressing(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + void ChassisGimbalShooterCoverManual::ctrlZPress() { if (!cover_command_sender_->getState()) From 2a16eea62cee1cc68daacb8277877760bd27c9b5 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 13:33:21 +0800 Subject: [PATCH 11/31] Use function from parent class. --- src/chassis_gimbal_shooter_cover_manual.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 16afc88d..4609313a 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -167,14 +167,11 @@ void ChassisGimbalShooterCoverManual::cPress() { if (is_gyro_) { - chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::FOLLOW); - vel_cmd_sender_->setAngularZVel(0.0); - is_gyro_ = false; + setChassisMode(rm_msgs::ChassisCmd::FOLLOW); } else { - chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::RAW); - is_gyro_ = true; + setChassisMode(rm_msgs::ChassisCmd::RAW); chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL); if (x_scale_ != 0.0 || y_scale_ != 0.0) { From 4a8c9559b63ebd2273ae8601c45737693565a0a2 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:29:10 +0800 Subject: [PATCH 12/31] Add slow mode for gyro's different speed. --- include/rm_manual/chassis_gimbal_manual.h | 1 + .../chassis_gimbal_shooter_cover_manual.h | 6 ++ src/chassis_gimbal_manual.cpp | 4 +- src/chassis_gimbal_shooter_cover_manual.cpp | 76 ++++++++++++------- 4 files changed, 58 insertions(+), 29 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_manual.h b/include/rm_manual/chassis_gimbal_manual.h index 6c07ed8b..91f55491 100644 --- a/include/rm_manual/chassis_gimbal_manual.h +++ b/include/rm_manual/chassis_gimbal_manual.h @@ -64,6 +64,7 @@ class ChassisGimbalManual : public ManualBase double x_scale_{}, y_scale_{}; bool is_gyro_{ 0 }; double speed_change_scale_{ 1. }; + double gyro_speed_change_scale_{ 1. }; double gimbal_scale_{ 1. }; double gyro_move_reduction_{ 1. }; double gyro_rotate_reduction_{ 1. }; diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index defce76b..031ca0a3 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -20,6 +20,7 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual protected: void changeSpeedMode(SpeedMode speed_mode); + void changeGyroSpeedMode(SpeedMode speed_mode); void updatePc(const rm_msgs::DbusData::ConstPtr& dbus_data) override; void checkKeyboard(const rm_msgs::DbusData::ConstPtr& dbus_data) override; void checkReferee() override; @@ -38,6 +39,10 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void aPressing() override; void sPressing() override; void dPressing() override; + void wRelease() override; + void aRelease() override; + void sRelease() override; + void dRelease() override; virtual void ctrlZPress(); virtual void ctrlZRelease() @@ -45,6 +50,7 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE); }; double low_speed_scale_{}, normal_speed_scale_{}; + double low_gyro_speed_scale_{}, normal_gyro_speed_scale_{}; double exit_buff_mode_duration_{}; double buff_gyro_rotate_limit_{}; rm_common::SwitchDetectionCaller* switch_buff_srv_{}; diff --git a/src/chassis_gimbal_manual.cpp b/src/chassis_gimbal_manual.cpp index efd171ec..50f28f41 100644 --- a/src/chassis_gimbal_manual.cpp +++ b/src/chassis_gimbal_manual.cpp @@ -230,9 +230,9 @@ void ChassisGimbalManual::setChassisMode(int mode) chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::RAW); is_gyro_ = true; if (x_scale_ != 0.0 || y_scale_ != 0.0) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_ * gyro_speed_change_scale_); else - vel_cmd_sender_->setAngularZVel(1.0); + vel_cmd_sender_->setAngularZVel(1.0 * gyro_speed_change_scale_); break; case rm_msgs::ChassisCmd::FOLLOW: chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::FOLLOW); diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 4609313a..f222be47 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -21,6 +21,8 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle ros::NodeHandle chassis_nh(nh, "chassis"); normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); + normal_gyro_speed_scale_ = chassis_nh.param("normal_gryo_speed_scale", 1); + low_gyro_speed_scale_ = chassis_nh.param("low_gyro_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 6.0); @@ -43,6 +45,18 @@ void ChassisGimbalShooterCoverManual::changeSpeedMode(SpeedMode speed_mode) } } +void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode speed_mode) +{ + if (speed_mode == LOW) + { + gyro_speed_change_scale_ = low_gyro_speed_scale_; + } + else if (speed_mode == NORMAL) + { + gyro_speed_change_scale_ = normal_gyro_speed_scale_; + } +} + void ChassisGimbalShooterCoverManual::updatePc(const rm_msgs::DbusData::ConstPtr& dbus_data) { ChassisGimbalShooterManual::updatePc(dbus_data); @@ -165,29 +179,9 @@ void ChassisGimbalShooterCoverManual::ePress() void ChassisGimbalShooterCoverManual::cPress() { - if (is_gyro_) - { - setChassisMode(rm_msgs::ChassisCmd::FOLLOW); - } - else - { - setChassisMode(rm_msgs::ChassisCmd::RAW); - chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL); - if (x_scale_ != 0.0 || y_scale_ != 0.0) - { - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::SMALL_BUFF) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); - else - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); - } - else - { - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::SMALL_BUFF) - vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); - else - vel_cmd_sender_->setAngularZVel(1.0); - } - } + ChassisGimbalShooterManual::cPress(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); } void ChassisGimbalShooterCoverManual::zPress() @@ -223,7 +217,7 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + changeGyroSpeedMode(LOW); } } @@ -231,23 +225,51 @@ void ChassisGimbalShooterCoverManual::aPressing() { ChassisGimbalShooterManual::aPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + changeGyroSpeedMode(LOW); } void ChassisGimbalShooterCoverManual::sPressing() { ChassisGimbalShooterManual::sPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + changeGyroSpeedMode(LOW); } void ChassisGimbalShooterCoverManual::dPressing() { ChassisGimbalShooterManual::dPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + changeGyroSpeedMode(LOW); } +void ChassisGimbalShooterCoverManual::wRelease() +{ + ChassisGimbalShooterManual::wRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); +}; + +void ChassisGimbalShooterCoverManual::aRelease() +{ + ChassisGimbalShooterManual::aRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); +}; + +void ChassisGimbalShooterCoverManual::sRelease() +{ + ChassisGimbalShooterManual::sRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); +}; + +void ChassisGimbalShooterCoverManual::dRelease() +{ + ChassisGimbalShooterManual::dRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); +}; + void ChassisGimbalShooterCoverManual::ctrlZPress() { if (!cover_command_sender_->getState()) From 225af6c7f31352acb792f9b2d03b855f0c041627 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:47:52 +0800 Subject: [PATCH 13/31] Make a supplement. --- src/chassis_gimbal_shooter_cover_manual.cpp | 19 ++----------------- 1 file changed, 2 insertions(+), 17 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index f222be47..f0ae2f2e 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -158,23 +158,8 @@ void ChassisGimbalShooterCoverManual::ePress() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); - if (is_gyro_) - { - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR) - { - if (x_scale_ != 0.0 || y_scale_ != 0.0) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); - else - vel_cmd_sender_->setAngularZVel(1.0); - } - else - { - if (x_scale_ != 0.0 || y_scale_ != 0.0) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); - else - vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); - } - } + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(LOW); } void ChassisGimbalShooterCoverManual::cPress() From 043c11427e8c1dc6545c88f5c93bc8e9bf2be0b4 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:48:51 +0800 Subject: [PATCH 14/31] Make a reset. --- src/chassis_gimbal_shooter_cover_manual.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index f0ae2f2e..856016f3 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -201,8 +201,8 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(NORMAL); } } From e5865b54323876b87f2a9c3811484737917770e6 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:49:56 +0800 Subject: [PATCH 15/31] Make a reset. --- src/chassis_gimbal_shooter_cover_manual.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 856016f3..a376c342 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -209,22 +209,22 @@ void ChassisGimbalShooterCoverManual::wPressing() void ChassisGimbalShooterCoverManual::aPressing() { ChassisGimbalShooterManual::aPressing(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(NORMAL); } void ChassisGimbalShooterCoverManual::sPressing() { ChassisGimbalShooterManual::sPressing(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(NORMAL); } void ChassisGimbalShooterCoverManual::dPressing() { ChassisGimbalShooterManual::dPressing(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + changeGyroSpeedMode(NORMAL); } void ChassisGimbalShooterCoverManual::wRelease() From a7359670e7f2ee3c3028966c8b529f1589f7ab5b Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:52:05 +0800 Subject: [PATCH 16/31] Delete something unused. --- include/rm_manual/chassis_gimbal_shooter_cover_manual.h | 1 - src/chassis_gimbal_shooter_cover_manual.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index 031ca0a3..0a86a00c 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -52,7 +52,6 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual double low_speed_scale_{}, normal_speed_scale_{}; double low_gyro_speed_scale_{}, normal_gyro_speed_scale_{}; double exit_buff_mode_duration_{}; - double buff_gyro_rotate_limit_{}; rm_common::SwitchDetectionCaller* switch_buff_srv_{}; rm_common::SwitchDetectionCaller* switch_buff_type_srv_{}; rm_common::SwitchDetectionCaller* switch_exposure_srv_{}; diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index a376c342..7fa533e8 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -24,7 +24,6 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle normal_gyro_speed_scale_ = chassis_nh.param("normal_gryo_speed_scale", 1); low_gyro_speed_scale_ = chassis_nh.param("low_gyro_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); - nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 6.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); From 050c2edef7feb74c23138bc2a9bd1f921db284dc Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:52:37 +0800 Subject: [PATCH 17/31] Fix wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 7fa533e8..32a07e52 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -21,7 +21,7 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle ros::NodeHandle chassis_nh(nh, "chassis"); normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); - normal_gyro_speed_scale_ = chassis_nh.param("normal_gryo_speed_scale", 1); + normal_gyro_speed_scale_ = chassis_nh.param("normal_gyro_speed_scale", 1); low_gyro_speed_scale_ = chassis_nh.param("low_gyro_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); From 06b9d508dd999d0832faa780dd5b6efe57089fe4 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 20:53:45 +0800 Subject: [PATCH 18/31] Modify name. --- src/chassis_gimbal_shooter_cover_manual.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 32a07e52..8597dcfb 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -44,13 +44,13 @@ void ChassisGimbalShooterCoverManual::changeSpeedMode(SpeedMode speed_mode) } } -void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode speed_mode) +void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode gyro_speed_mode) { - if (speed_mode == LOW) + if (gyro_speed_mode == LOW) { gyro_speed_change_scale_ = low_gyro_speed_scale_; } - else if (speed_mode == NORMAL) + else if (gyro_speed_mode == NORMAL) { gyro_speed_change_scale_ = normal_gyro_speed_scale_; } From c815f00be7d38e1c39333cf6589f064447bd3b65 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:09:33 +0800 Subject: [PATCH 19/31] Make a supplement. --- src/chassis_gimbal_shooter_manual.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 6e28e1be..c70ffddc 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -501,45 +501,45 @@ void ChassisGimbalShooterManual::dPress() void ChassisGimbalShooterManual::wRelease() { ChassisGimbalManual::wRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::aRelease() { ChassisGimbalManual::aRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::sRelease() { ChassisGimbalManual::sRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::dRelease() { ChassisGimbalManual::dRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::wPressing() { ChassisGimbalManual::wPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::aPressing() { ChassisGimbalManual::aPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::sPressing() { ChassisGimbalManual::sPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::dPressing() { ChassisGimbalManual::dPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); } void ChassisGimbalShooterManual::xPress() From 1153b72881f485393ff730f8b645ec90e63e50bc Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:10:15 +0800 Subject: [PATCH 20/31] Delete something unused. --- .../chassis_gimbal_shooter_cover_manual.h | 4 --- src/chassis_gimbal_shooter_cover_manual.cpp | 28 ------------------- 2 files changed, 32 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index 0a86a00c..e0b7c244 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -39,10 +39,6 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void aPressing() override; void sPressing() override; void dPressing() override; - void wRelease() override; - void aRelease() override; - void sRelease() override; - void dRelease() override; virtual void ctrlZPress(); virtual void ctrlZRelease() diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 8597dcfb..9ae7c249 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -226,34 +226,6 @@ void ChassisGimbalShooterCoverManual::dPressing() changeGyroSpeedMode(NORMAL); } -void ChassisGimbalShooterCoverManual::wRelease() -{ - ChassisGimbalShooterManual::wRelease(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); -}; - -void ChassisGimbalShooterCoverManual::aRelease() -{ - ChassisGimbalShooterManual::aRelease(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); -}; - -void ChassisGimbalShooterCoverManual::sRelease() -{ - ChassisGimbalShooterManual::sRelease(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); -}; - -void ChassisGimbalShooterCoverManual::dRelease() -{ - ChassisGimbalShooterManual::dRelease(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); -}; - void ChassisGimbalShooterCoverManual::ctrlZPress() { if (!cover_command_sender_->getState()) From f726e5d4588f6df9786042e9d9db04c6fd39b0de Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:12:19 +0800 Subject: [PATCH 21/31] Make a supplement. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 9ae7c249..ab41ba5a 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -166,6 +166,8 @@ void ChassisGimbalShooterCoverManual::cPress() ChassisGimbalShooterManual::cPress(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) changeGyroSpeedMode(LOW); + else + changeGyroSpeedMode(NORMAL); } void ChassisGimbalShooterCoverManual::zPress() From bd59fb99c227d84deb1541612fcb7d75dcaac211 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:13:19 +0800 Subject: [PATCH 22/31] Delete something unused. --- .../chassis_gimbal_shooter_cover_manual.h | 3 --- src/chassis_gimbal_shooter_cover_manual.cpp | 23 ------------------- 2 files changed, 26 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index e0b7c244..999fa9c8 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -36,9 +36,6 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void ctrlRRelease() override; void wPress() override; void wPressing() override; - void aPressing() override; - void sPressing() override; - void dPressing() override; virtual void ctrlZPress(); virtual void ctrlZRelease() diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index ab41ba5a..ef1d33ce 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -202,32 +202,9 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(NORMAL); } } -void ChassisGimbalShooterCoverManual::aPressing() -{ - ChassisGimbalShooterManual::aPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(NORMAL); -} - -void ChassisGimbalShooterCoverManual::sPressing() -{ - ChassisGimbalShooterManual::sPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(NORMAL); -} - -void ChassisGimbalShooterCoverManual::dPressing() -{ - ChassisGimbalShooterManual::dPressing(); - if (switch_buff_srv_->getTarget() == rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(NORMAL); -} - void ChassisGimbalShooterCoverManual::ctrlZPress() { if (!cover_command_sender_->getState()) From 15c6831b6db36a5169c39c3f780343c9758ac2d1 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:45:19 +0800 Subject: [PATCH 23/31] Modify method to achieve gyro speed slower when shooting buff. --- include/rm_manual/chassis_gimbal_manual.h | 1 - .../chassis_gimbal_shooter_cover_manual.h | 9 +- src/chassis_gimbal_manual.cpp | 4 +- src/chassis_gimbal_shooter_cover_manual.cpp | 93 ++++++++++++++++--- src/chassis_gimbal_shooter_manual.cpp | 16 ++-- 5 files changed, 98 insertions(+), 25 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_manual.h b/include/rm_manual/chassis_gimbal_manual.h index 91f55491..6c07ed8b 100644 --- a/include/rm_manual/chassis_gimbal_manual.h +++ b/include/rm_manual/chassis_gimbal_manual.h @@ -64,7 +64,6 @@ class ChassisGimbalManual : public ManualBase double x_scale_{}, y_scale_{}; bool is_gyro_{ 0 }; double speed_change_scale_{ 1. }; - double gyro_speed_change_scale_{ 1. }; double gimbal_scale_{ 1. }; double gyro_move_reduction_{ 1. }; double gyro_rotate_reduction_{ 1. }; diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index 999fa9c8..d9f67d0e 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -36,6 +36,13 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual void ctrlRRelease() override; void wPress() override; void wPressing() override; + void aPressing() override; + void sPressing() override; + void dPressing() override; + void wRelease() override; + void aRelease() override; + void sRelease() override; + void dRelease() override; virtual void ctrlZPress(); virtual void ctrlZRelease() @@ -43,8 +50,8 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE); }; double low_speed_scale_{}, normal_speed_scale_{}; - double low_gyro_speed_scale_{}, normal_gyro_speed_scale_{}; double exit_buff_mode_duration_{}; + double buff_gyro_rotate_limit_{}; rm_common::SwitchDetectionCaller* switch_buff_srv_{}; rm_common::SwitchDetectionCaller* switch_buff_type_srv_{}; rm_common::SwitchDetectionCaller* switch_exposure_srv_{}; diff --git a/src/chassis_gimbal_manual.cpp b/src/chassis_gimbal_manual.cpp index 50f28f41..efd171ec 100644 --- a/src/chassis_gimbal_manual.cpp +++ b/src/chassis_gimbal_manual.cpp @@ -230,9 +230,9 @@ void ChassisGimbalManual::setChassisMode(int mode) chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::RAW); is_gyro_ = true; if (x_scale_ != 0.0 || y_scale_ != 0.0) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_ * gyro_speed_change_scale_); + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); else - vel_cmd_sender_->setAngularZVel(1.0 * gyro_speed_change_scale_); + vel_cmd_sender_->setAngularZVel(1.0); break; case rm_msgs::ChassisCmd::FOLLOW: chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::FOLLOW); diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index ef1d33ce..b64024ea 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -21,9 +21,8 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle ros::NodeHandle chassis_nh(nh, "chassis"); normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); - normal_gyro_speed_scale_ = chassis_nh.param("normal_gyro_speed_scale", 1); - low_gyro_speed_scale_ = chassis_nh.param("low_gyro_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); + nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 9.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); @@ -44,15 +43,21 @@ void ChassisGimbalShooterCoverManual::changeSpeedMode(SpeedMode speed_mode) } } -void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode gyro_speed_mode) +void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode speed_mode) { - if (gyro_speed_mode == LOW) + if (speed_mode == LOW) { - gyro_speed_change_scale_ = low_gyro_speed_scale_; + if (x_scale_ != 0.0 || y_scale_ != 0.0) + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); + else + vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); } - else if (gyro_speed_mode == NORMAL) + else if (speed_mode == NORMAL) { - gyro_speed_change_scale_ = normal_gyro_speed_scale_; + if (x_scale_ != 0.0 || y_scale_ != 0.0) + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_); + else + vel_cmd_sender_->setAngularZVel(1.0); } } @@ -157,23 +162,38 @@ void ChassisGimbalShooterCoverManual::ePress() switch_detection_srv_->callService(); switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (is_gyro_) + { + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + changeGyroSpeedMode(LOW); + else + changeGyroSpeedMode(NORMAL); + } } void ChassisGimbalShooterCoverManual::cPress() { - ChassisGimbalShooterManual::cPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) - changeGyroSpeedMode(LOW); + if (is_gyro_) + { + setChassisMode(rm_msgs::ChassisCmd::FOLLOW); + } else - changeGyroSpeedMode(NORMAL); + { + setChassisMode(rm_msgs::ChassisCmd::RAW); + chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + changeGyroSpeedMode(LOW); + else + changeGyroSpeedMode(NORMAL); + } } void ChassisGimbalShooterCoverManual::zPress() { last_shoot_freq_ = shooter_cmd_sender_->getShootFrequency(); shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::MINIMAL); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } void ChassisGimbalShooterCoverManual::zRelease() @@ -203,8 +223,55 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_buff_type_srv_->callService(); switch_exposure_srv_->callService(); } + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::aPressing() +{ + ChassisGimbalShooterManual::aPressing(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } +void ChassisGimbalShooterCoverManual::sPressing() +{ + ChassisGimbalShooterManual::sPressing(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::dPressing() +{ + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); +} + +void ChassisGimbalShooterCoverManual::wRelease() +{ + ChassisGimbalShooterManual::wRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +}; +void ChassisGimbalShooterCoverManual::aRelease() +{ + ChassisGimbalShooterManual::aRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +}; +void ChassisGimbalShooterCoverManual::sRelease() +{ + ChassisGimbalShooterManual::sRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +}; +void ChassisGimbalShooterCoverManual::dRelease() +{ + ChassisGimbalShooterManual::dRelease(); + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); +}; + void ChassisGimbalShooterCoverManual::ctrlZPress() { if (!cover_command_sender_->getState()) diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index c70ffddc..6e28e1be 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -501,45 +501,45 @@ void ChassisGimbalShooterManual::dPress() void ChassisGimbalShooterManual::wRelease() { ChassisGimbalManual::wRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); } void ChassisGimbalShooterManual::aRelease() { ChassisGimbalManual::aRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); } void ChassisGimbalShooterManual::sRelease() { ChassisGimbalManual::sRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); } void ChassisGimbalShooterManual::dRelease() { ChassisGimbalManual::dRelease(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0); } void ChassisGimbalShooterManual::wPressing() { ChassisGimbalManual::wPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); } void ChassisGimbalShooterManual::aPressing() { ChassisGimbalManual::aPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); } void ChassisGimbalShooterManual::sPressing() { ChassisGimbalManual::sPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); } void ChassisGimbalShooterManual::dPressing() { ChassisGimbalManual::dPressing(); - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ * gyro_speed_change_scale_ : 0); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0); } void ChassisGimbalShooterManual::xPress() From 79f2c08334413373fd7962faf25b523c46c71e31 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:48:45 +0800 Subject: [PATCH 24/31] Fix wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index b64024ea..166995e7 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -204,7 +204,7 @@ void ChassisGimbalShooterCoverManual::zRelease() void ChassisGimbalShooterCoverManual::wPress() { ChassisGimbalShooterManual::wPress(); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR && is_gyro_) + if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) last_switch_time_ = ros::Time::now(); } From 268a963b24e074cc59fb476e5b889678fd42d9a1 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 21:54:56 +0800 Subject: [PATCH 25/31] Delete unused. --- src/chassis_gimbal_shooter_manual.cpp | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 6e28e1be..b3cbc881 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -425,18 +425,15 @@ void ChassisGimbalShooterManual::bRelease() void ChassisGimbalShooterManual::rPress() { - if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_HERO || robot_id_ == rm_msgs::GameRobotStatus::RED_HERO) + if (scope_cmd_sender_) { - if (scope_cmd_sender_) + use_scope_ = !scope_cmd_sender_->getState(); + if (use_scope_) + gimbal_cmd_sender_->setEject(true); + else { - use_scope_ = !scope_cmd_sender_->getState(); - if (use_scope_) - gimbal_cmd_sender_->setEject(true); - else - { - gimbal_cmd_sender_->setEject(false); - adjust_image_transmission_ = false; - } + gimbal_cmd_sender_->setEject(false); + adjust_image_transmission_ = false; } } } From 727b585e2ec8f9282714f92f8e75ed2603d7b3d1 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 22:10:50 +0800 Subject: [PATCH 26/31] Fix wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 166995e7..c6fa9d2a 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -243,6 +243,7 @@ void ChassisGimbalShooterCoverManual::sPressing() void ChassisGimbalShooterCoverManual::dPressing() { + ChassisGimbalShooterManual::dPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); } From 67eb41762f7a7f7920cd2331fa33aa6d808aac1f Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 22:26:12 +0800 Subject: [PATCH 27/31] Modify value. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index c6fa9d2a..46d27257 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -22,7 +22,7 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); - nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 9.0); + nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 6.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); From f69b7c04c9d749076acf6125b0b2388398040302 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 22:53:16 +0800 Subject: [PATCH 28/31] Modify param name. --- .../chassis_gimbal_shooter_cover_manual.h | 2 +- src/chassis_gimbal_shooter_cover_manual.cpp | 24 +++++++++---------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h index d9f67d0e..3a37660f 100644 --- a/include/rm_manual/chassis_gimbal_shooter_cover_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_cover_manual.h @@ -51,7 +51,7 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual }; double low_speed_scale_{}, normal_speed_scale_{}; double exit_buff_mode_duration_{}; - double buff_gyro_rotate_limit_{}; + double gyro_speed_limit_{}; rm_common::SwitchDetectionCaller* switch_buff_srv_{}; rm_common::SwitchDetectionCaller* switch_buff_type_srv_{}; rm_common::SwitchDetectionCaller* switch_exposure_srv_{}; diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 46d27257..6fa27890 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -22,7 +22,7 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); - nh.param("buff_gyro_rotate_limit", buff_gyro_rotate_limit_, 6.0); + nh.param("buff_gyro_rotate_limit", gyro_speed_limit_, 6.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); @@ -48,9 +48,9 @@ void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode speed_mode) if (speed_mode == LOW) { if (x_scale_ != 0.0 || y_scale_ != 0.0) - vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_, gyro_speed_limit_); else - vel_cmd_sender_->setAngularZVel(1.0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(1.0, gyro_speed_limit_); } else if (speed_mode == NORMAL) { @@ -193,7 +193,7 @@ void ChassisGimbalShooterCoverManual::zPress() last_shoot_freq_ = shooter_cmd_sender_->getShootFrequency(); shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::MINIMAL); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::zRelease() @@ -224,53 +224,53 @@ void ChassisGimbalShooterCoverManual::wPressing() switch_exposure_srv_->callService(); } if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::aPressing() { ChassisGimbalShooterManual::aPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::sPressing() { ChassisGimbalShooterManual::sPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::dPressing() { ChassisGimbalShooterManual::dPressing(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::wRelease() { ChassisGimbalShooterManual::wRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); }; void ChassisGimbalShooterCoverManual::aRelease() { ChassisGimbalShooterManual::aRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); }; void ChassisGimbalShooterCoverManual::sRelease() { ChassisGimbalShooterManual::sRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); }; void ChassisGimbalShooterCoverManual::dRelease() { ChassisGimbalShooterManual::dRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, buff_gyro_rotate_limit_); + vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); }; void ChassisGimbalShooterCoverManual::ctrlZPress() From 13033a8aadec055cf9c189ad2d593f1c7383d5e0 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 22:54:43 +0800 Subject: [PATCH 29/31] Modify param name and fix wrong. --- src/chassis_gimbal_shooter_cover_manual.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 6fa27890..1a296186 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -253,25 +253,28 @@ void ChassisGimbalShooterCoverManual::wRelease() ChassisGimbalShooterManual::wRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); -}; +} + void ChassisGimbalShooterCoverManual::aRelease() { ChassisGimbalShooterManual::aRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); -}; +} + void ChassisGimbalShooterCoverManual::sRelease() { ChassisGimbalShooterManual::sRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); -}; +} + void ChassisGimbalShooterCoverManual::dRelease() { ChassisGimbalShooterManual::dRelease(); if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) vel_cmd_sender_->setAngularZVel(is_gyro_ ? 1 : 0, gyro_speed_limit_); -}; +} void ChassisGimbalShooterCoverManual::ctrlZPress() { From f7d05593af55fea0fa6bdda06276cee39f0f7ec9 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 22:58:23 +0800 Subject: [PATCH 30/31] Modify param name. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 1a296186..212f25ba 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -22,7 +22,7 @@ ChassisGimbalShooterCoverManual::ChassisGimbalShooterCoverManual(ros::NodeHandle normal_speed_scale_ = chassis_nh.param("normal_speed_scale", 1); low_speed_scale_ = chassis_nh.param("low_speed_scale", 0.30); nh.param("exit_buff_mode_duration", exit_buff_mode_duration_, 0.5); - nh.param("buff_gyro_rotate_limit", gyro_speed_limit_, 6.0); + nh.param("gyro_speed_limit", gyro_speed_limit_, 6.0); ctrl_z_event_.setEdge(boost::bind(&ChassisGimbalShooterCoverManual::ctrlZPress, this), boost::bind(&ChassisGimbalShooterCoverManual::ctrlZRelease, this)); From 4513b83190092fe1d1f6232e27f650cffae48cc4 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Sun, 4 Aug 2024 23:11:10 +0800 Subject: [PATCH 31/31] Delete unused. --- src/chassis_gimbal_shooter_cover_manual.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/chassis_gimbal_shooter_cover_manual.cpp b/src/chassis_gimbal_shooter_cover_manual.cpp index 212f25ba..73a92802 100644 --- a/src/chassis_gimbal_shooter_cover_manual.cpp +++ b/src/chassis_gimbal_shooter_cover_manual.cpp @@ -192,8 +192,6 @@ void ChassisGimbalShooterCoverManual::zPress() { last_shoot_freq_ = shooter_cmd_sender_->getShootFrequency(); shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::MINIMAL); - if (switch_buff_srv_->getTarget() != rm_msgs::StatusChangeRequest::ARMOR) - vel_cmd_sender_->setAngularZVel(is_gyro_ ? gyro_rotate_reduction_ : 0, gyro_speed_limit_); } void ChassisGimbalShooterCoverManual::zRelease()