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

Transform static variable into member #220

Merged
merged 1 commit into from
Mar 18, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
1 change: 1 addition & 0 deletions velodyne_driver/include/velodyne_driver/driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ class VelodyneDriver

boost::shared_ptr<Input> input_;
ros::Publisher output_;
int last_azimuth_;

/** diagnostics updater */
ros::Timer diag_timer_;
Expand Down
19 changes: 10 additions & 9 deletions velodyne_driver/src/driver/driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,8 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
// raw packet output topic
output_ =
node.advertise<velodyne_msgs::VelodyneScan>("velodyne_packets", 10);

last_azimuth_ = -1;
}

/** poll the device
Expand All @@ -177,24 +179,23 @@ bool VelodyneDriver::poll(void)
}
scan->packets.push_back(tmp_packet);

static int last_azimuth = -1;
// Extract base rotation of first block in packet
std::size_t azimuth_data_pos = 100*0+2;
int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));

//if first packet in scan, there is no "valid" last_azimuth
if (last_azimuth == -1) {
last_azimuth = azimuth;
//if first packet in scan, there is no "valid" last_azimuth_
if (last_azimuth_ == -1) {
last_azimuth_ = azimuth;
continue;
}
if((last_azimuth < config_.cut_angle && config_.cut_angle <= azimuth)
|| ( config_.cut_angle <= azimuth && azimuth < last_azimuth)
|| (azimuth < last_azimuth && last_azimuth < config_.cut_angle))
if((last_azimuth_ < config_.cut_angle && config_.cut_angle <= azimuth)
|| ( config_.cut_angle <= azimuth && azimuth < last_azimuth_)
|| (azimuth < last_azimuth_ && last_azimuth_ < config_.cut_angle))
{
last_azimuth = azimuth;
last_azimuth_ = azimuth;
break; // Cut angle passed, one full revolution collected
}
last_azimuth = azimuth;
last_azimuth_ = azimuth;
}
}
else // standard behaviour
Expand Down