Skip to content

Commit

Permalink
Modify the code for cleanliness.
Browse files Browse the repository at this point in the history
  • Loading branch information
liyixin135 committed Jul 8, 2024
1 parent 0c9a8af commit 8cb89e1
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 32 deletions.
2 changes: 2 additions & 0 deletions include/rm_manual/chassis_gimbal_shooter_cover_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
56 changes: 24 additions & 32 deletions src/chassis_gimbal_shooter_cover_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand All @@ -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

0 comments on commit 8cb89e1

Please sign in to comment.