diff --git a/include/rm_manual/chassis_gimbal_shooter_manual.h b/include/rm_manual/chassis_gimbal_shooter_manual.h index 7766afb8..2c468f8b 100644 --- a/include/rm_manual/chassis_gimbal_shooter_manual.h +++ b/include/rm_manual/chassis_gimbal_shooter_manual.h @@ -64,7 +64,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE); if (shooter_cmd_sender_->getMsg()->mode == rm_msgs::ShootCmd::PUSH) shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::READY); - turn_flag_ = false; + is_mouse_right_press_ = false; } void wPress() override; void aPress() override; @@ -122,7 +122,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual geometry_msgs::PointStamped point_out_; bool prepare_shoot_ = false, turn_flag_ = false, is_balance_ = false, use_scope_ = false, - adjust_image_transmission_ = false; + adjust_image_transmission_ = false, is_mouse_right_press_ = false; double yaw_current_{}; }; } // namespace rm_manual diff --git a/src/chassis_gimbal_shooter_manual.cpp b/src/chassis_gimbal_shooter_manual.cpp index 40bea015..a9074095 100644 --- a/src/chassis_gimbal_shooter_manual.cpp +++ b/src/chassis_gimbal_shooter_manual.cpp @@ -189,6 +189,7 @@ void ChassisGimbalShooterManual::remoteControlTurnOff() shooter_calibration_->stop(); gimbal_calibration_->stop(); turn_flag_ = false; + is_mouse_right_press_ = false; use_scope_ = false; adjust_image_transmission_ = false; } @@ -207,6 +208,7 @@ void ChassisGimbalShooterManual::robotDie() ManualBase::robotDie(); shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::STOP); turn_flag_ = false; + is_mouse_right_press_ = false; use_scope_ = false; adjust_image_transmission_ = false; } @@ -344,7 +346,7 @@ void ChassisGimbalShooterManual::mouseLeftPress() } if (prepare_shoot_) { - if (!turn_flag_ || (turn_flag_ && track_data_.id != 0)) + if (!is_mouse_right_press_ || (is_mouse_right_press_ && track_data_.id != 0)) { shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::PUSH); shooter_cmd_sender_->checkError(ros::Time::now()); @@ -356,7 +358,7 @@ void ChassisGimbalShooterManual::mouseLeftPress() void ChassisGimbalShooterManual::mouseRightPress() { - turn_flag_ = true; + is_mouse_right_press_ = true; if (track_data_.id == 0) gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE); else