Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Slow gyro's speed when shooting buff #100

Merged
merged 33 commits into from
Aug 4, 2024
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
c85d948
Add one judgement for rPress.
liyixin135 May 28, 2024
e6ea897
Slow down the shooter's frequency when shooting buff.
liyixin135 May 29, 2024
de4241d
Replace zPress to zPressing for slowing down shooter's frequency,slow…
liyixin135 May 30, 2024
0c9a8af
Modify something wrong.
liyixin135 May 30, 2024
8cb89e1
Modify the code for cleanliness.
liyixin135 Jul 8, 2024
9972018
Merge branch 'master' into standard1
liyixin135 Jul 18, 2024
0d20bfd
Merge branch 'master' into standard1
liyixin135 Aug 1, 2024
d8220ef
Fix wrong from merge.
liyixin135 Aug 1, 2024
3b8b33d
Delete something unused.
liyixin135 Aug 1, 2024
fe64e3d
Slow gyro's speed when shoot buff through wasdPress.
liyixin135 Aug 3, 2024
930eedc
Fix wrong.
liyixin135 Aug 3, 2024
89c2464
Fix wrong.
liyixin135 Aug 4, 2024
2a16eea
Use function from parent class.
liyixin135 Aug 4, 2024
4a8c955
Add slow mode for gyro's different speed.
liyixin135 Aug 4, 2024
225af6c
Make a supplement.
liyixin135 Aug 4, 2024
043c114
Make a reset.
liyixin135 Aug 4, 2024
e5865b5
Make a reset.
liyixin135 Aug 4, 2024
a735967
Delete something unused.
liyixin135 Aug 4, 2024
050c2ed
Fix wrong.
liyixin135 Aug 4, 2024
06b9d50
Modify name.
liyixin135 Aug 4, 2024
c815f00
Make a supplement.
liyixin135 Aug 4, 2024
1153b72
Delete something unused.
liyixin135 Aug 4, 2024
f726e5d
Make a supplement.
liyixin135 Aug 4, 2024
bd59fb9
Delete something unused.
liyixin135 Aug 4, 2024
15c6831
Modify method to achieve gyro speed slower when shooting buff.
liyixin135 Aug 4, 2024
79f2c08
Fix wrong.
liyixin135 Aug 4, 2024
268a963
Delete unused.
liyixin135 Aug 4, 2024
727b585
Fix wrong.
liyixin135 Aug 4, 2024
67eb417
Modify value.
liyixin135 Aug 4, 2024
f69b7c0
Modify param name.
liyixin135 Aug 4, 2024
13033a8
Modify param name and fix wrong.
liyixin135 Aug 4, 2024
f7d0559
Modify param name.
liyixin135 Aug 4, 2024
4513b83
Delete unused.
liyixin135 Aug 4, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 13 additions & 3 deletions include/rm_manual/chassis_gimbal_shooter_cover_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,23 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual
void rightSwitchDownRise() override;
void rightSwitchMidRise() override;
void rightSwitchUpRise() override;
void rPress() override;
void ePress() override;
void cPress() override;
void zPress();
void zRelease();
void wPress() override;
void wPressing() override;
void ctrlRPressing();
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;
void setAngularVelByTargetWhenMov();
void setAngularVelByTargetWhenStopMov();

virtual void ctrlZPress();
virtual void ctrlZRelease()
Expand All @@ -43,6 +52,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_{};
Expand Down
2 changes: 1 addition & 1 deletion include/rm_manual/chassis_gimbal_shooter_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,10 +88,10 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
virtual void cPress();
virtual void bPress();
virtual void bRelease();
virtual void rPress();
virtual void xRelease();
virtual void shiftPress();
virtual void shiftRelease();
void rPress();
void qPress()
{
shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::BURST);
Expand Down
122 changes: 107 additions & 15 deletions src/chassis_gimbal_shooter_cover_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +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);
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
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));
Expand Down Expand Up @@ -133,21 +134,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();
Expand All @@ -158,6 +144,53 @@ 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::zPress()
Expand Down Expand Up @@ -193,6 +226,49 @@ 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()
Expand Down Expand Up @@ -243,4 +319,20 @@ 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_);
}

liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
} // namespace rm_manual
19 changes: 10 additions & 9 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,17 +425,18 @@ 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)
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
{
use_scope_ = !scope_cmd_sender_->getState();
if (use_scope_)
gimbal_cmd_sender_->setEject(true);
else
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;
}
}
}
}
Expand Down
Loading