Skip to content

Commit 42c22a4

Browse files
committed
remove wrong comments
1 parent 1579a24 commit 42c22a4

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

bitbots_motion/bitbots_head_mover/src/move_head.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -717,14 +717,14 @@ class HeadMover {
717717
// Check if the head mode changed and if so, update the search pattern
718718
if (prev_head_mode_ != curr_head_mode) {
719719
switch (curr_head_mode) {
720-
case bitbots_msgs::msg::HeadMode::SEARCH_BALL: // 0
720+
case bitbots_msgs::msg::HeadMode::SEARCH_BALL:
721721
pan_speed_ = params_.search_pattern.pan_speed;
722722
tilt_speed_ = params_.search_pattern.tilt_speed;
723723
pattern_ = generatePattern(params_.search_pattern.scan_lines, params_.search_pattern.pan_max[0],
724724
params_.search_pattern.pan_max[1], params_.search_pattern.tilt_max[0],
725725
params_.search_pattern.tilt_max[1], params_.search_pattern.reduce_last_scanline);
726726
break;
727-
case bitbots_msgs::msg::HeadMode::SEARCH_BALL_PENALTY: // 11
727+
case bitbots_msgs::msg::HeadMode::SEARCH_BALL_PENALTY:
728728
pan_speed_ = params_.search_pattern_penalty.pan_speed;
729729
tilt_speed_ = params_.search_pattern_penalty.tilt_speed;
730730
pattern_ =
@@ -733,7 +733,7 @@ class HeadMover {
733733
params_.search_pattern_penalty.tilt_max[1], params_.search_pattern.reduce_last_scanline);
734734
break;
735735

736-
case bitbots_msgs::msg::HeadMode::SEARCH_FIELD_FEATURES: // 3
736+
case bitbots_msgs::msg::HeadMode::SEARCH_FIELD_FEATURES:
737737
pan_speed_ = params_.search_pattern_field_features.pan_speed;
738738
tilt_speed_ = params_.search_pattern_field_features.tilt_speed;
739739
pattern_ = generatePattern(
@@ -742,7 +742,7 @@ class HeadMover {
742742
params_.search_pattern_field_features.tilt_max[1], params_.search_pattern.reduce_last_scanline);
743743
break;
744744

745-
case bitbots_msgs::msg::HeadMode::SEARCH_FRONT: // 13
745+
case bitbots_msgs::msg::HeadMode::SEARCH_FRONT:
746746
pan_speed_ = params_.front_search_pattern.pan_speed;
747747
tilt_speed_ = params_.front_search_pattern.tilt_speed;
748748
pattern_ =
@@ -751,7 +751,7 @@ class HeadMover {
751751
params_.front_search_pattern.tilt_max[1], params_.search_pattern.reduce_last_scanline);
752752
break;
753753

754-
case bitbots_msgs::msg::HeadMode::LOOK_FORWARD: // 7
754+
case bitbots_msgs::msg::HeadMode::LOOK_FORWARD:
755755
pan_speed_ = params_.look_forward.pan_speed;
756756
tilt_speed_ = params_.look_forward.tilt_speed;
757757
pattern_ = generatePattern(params_.look_forward.scan_lines, params_.look_forward.pan_max[0],

0 commit comments

Comments
 (0)