Skip to content

Commit

Permalink
Modify to judge mouseRightPess.
Browse files Browse the repository at this point in the history
  • Loading branch information
liyixin135 committed Jul 9, 2024
1 parent dd973ba commit 7b782c3
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 6 deletions.
3 changes: 1 addition & 2 deletions include/rm_manual/chassis_gimbal_shooter_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,6 @@ 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);
is_mouse_right_press_ = false;
}
void wPress() override;
void aPress() override;
Expand Down Expand Up @@ -122,7 +121,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, is_mouse_right_press_ = false;
adjust_image_transmission_ = false;
double yaw_current_{};
};
} // namespace rm_manual
5 changes: 1 addition & 4 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,6 @@ void ChassisGimbalShooterManual::remoteControlTurnOff()
shooter_calibration_->stop();
gimbal_calibration_->stop();
turn_flag_ = false;
is_mouse_right_press_ = false;
use_scope_ = false;
adjust_image_transmission_ = false;
}
Expand All @@ -208,7 +207,6 @@ 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;
}
Expand Down Expand Up @@ -346,7 +344,7 @@ void ChassisGimbalShooterManual::mouseLeftPress()
}
if (prepare_shoot_)
{
if (!is_mouse_right_press_ || (is_mouse_right_press_ && track_data_.id != 0))
if (!mouse_right_event_.getState() || (mouse_right_event_.getState() && track_data_.id != 0))
{
shooter_cmd_sender_->setMode(rm_msgs::ShootCmd::PUSH);
shooter_cmd_sender_->checkError(ros::Time::now());
Expand All @@ -358,7 +356,6 @@ void ChassisGimbalShooterManual::mouseLeftPress()

void ChassisGimbalShooterManual::mouseRightPress()
{
is_mouse_right_press_ = true;
if (track_data_.id == 0)
gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE);
else
Expand Down

0 comments on commit 7b782c3

Please sign in to comment.