Skip to content

Commit

Permalink
Modify a param name.
Browse files Browse the repository at this point in the history
  • Loading branch information
liyixin135 committed Jul 26, 2024
1 parent 1b90fb4 commit 8b91573
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
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 @@ -131,7 +131,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
MOVE_BASE = 3
};

ros::Time hit_time_{};
ros::Time start_timer_time_{};

bool prepare_shoot_ = false, turn_flag_ = false, is_balance_ = false, use_scope_ = false, is_auto_ = false,
adjust_image_transmission_ = false;
Expand Down
8 changes: 4 additions & 4 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -635,12 +635,12 @@ void ChassisGimbalShooterManual::eventDataCallback(const rm_msgs::EventData::Con
if (data->be_hit_time != last_time_hit_by_dart_)
{
last_time_hit_by_dart_ = data->be_hit_time;
hit_time_ = ros::Time::now();
start_timer_time_ = ros::Time::now();
count_ = 0;
}
if ((data->be_hit_target == OUTPOST && (ros::Time::now() - hit_time_).toSec() <= 5) ||
(data->be_hit_target == BASE && (ros::Time::now() - hit_time_).toSec() <= 10) ||
(data->be_hit_target == MOVE_BASE && (ros::Time::now() - hit_time_).toSec() <= 15))
if ((data->be_hit_target == OUTPOST && (ros::Time::now() - start_timer_time_).toSec() <= 5) ||
(data->be_hit_target == BASE && (ros::Time::now() - start_timer_time_).toSec() <= 10) ||
(data->be_hit_target == MOVE_BASE && (ros::Time::now() - start_timer_time_).toSec() <= 15))
is_auto_ = true;
else
is_auto_ = false;
Expand Down

0 comments on commit 8b91573

Please sign in to comment.