Skip to content

Commit

Permalink
Standardlize some code.
Browse files Browse the repository at this point in the history
  • Loading branch information
Rayy0527 committed Dec 6, 2024
1 parent ea5e1cc commit bdc18f6
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 10 deletions.
5 changes: 1 addition & 4 deletions include/rm_manual/chassis_gimbal_shooter_cover_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,7 @@ class ChassisGimbalShooterCoverManual : public ChassisGimbalShooterManual
double low_speed_scale_{}, normal_speed_scale_{};
double exit_buff_mode_duration_{};
double gyro_speed_limit_{};
double sin_gyro_base_scale_{ 1. };
double sin_gyro_amplitude_{ 0. };
double sin_gyro_period_{ 1. };
double sin_gyro_phase_{ 0. };
double sin_gyro_base_scale_{ 1. }, sin_gyro_amplitude_{ 0. }, sin_gyro_period_{ 1. }, sin_gyro_phase_{ 0. };
rm_common::SwitchDetectionCaller* switch_buff_srv_{};
rm_common::SwitchDetectionCaller* switch_buff_type_srv_{};
rm_common::SwitchDetectionCaller* switch_exposure_srv_{};
Expand Down
10 changes: 4 additions & 6 deletions src/chassis_gimbal_shooter_cover_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ void ChassisGimbalShooterCoverManual::changeSpeedMode(SpeedMode speed_mode)
speed_change_scale_ = normal_speed_scale_;
}
}
double ChassisGimbalShooterCoverManual::getDynamicScale(double base_scale, double amplitude, double period, double phase)
double ChassisGimbalShooterCoverManual::getDynamicScale(const double base_scale, const double amplitude,
const double period, const double phase)
{
ros::Time current_time = ros::Time::now();
double t = current_time.toSec();
Expand Down Expand Up @@ -75,12 +76,9 @@ void ChassisGimbalShooterCoverManual::changeGyroSpeedMode(SpeedMode speed_mode)
else if (speed_mode == NORMAL)
{
if (x_scale_ != 0.0 || y_scale_ != 0.0)
vel_cmd_sender_->setAngularZVel(
getDynamicScale(sin_gyro_base_scale_, sin_gyro_amplitude_, sin_gyro_period_, sin_gyro_phase_) *
gyro_rotate_reduction_);
vel_cmd_sender_->setAngularZVel(gyro_rotate_reduction_);
else
vel_cmd_sender_->setAngularZVel(
getDynamicScale(sin_gyro_base_scale_, sin_gyro_amplitude_, sin_gyro_period_, sin_gyro_phase_));
vel_cmd_sender_->setAngularZVel(1.0);
}
}

Expand Down

0 comments on commit bdc18f6

Please sign in to comment.