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

Added support for laserscanners that spin clockwise #102

Merged
merged 1 commit into from
Feb 10, 2021
Merged
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
57 changes: 41 additions & 16 deletions include/laser_filters/angular_bounds_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,28 +73,53 @@ namespace laser_filters
unsigned int count = 0;
//loop through the scan and truncate the beginning and the end of the scan as necessary
for(unsigned int i = 0; i < input_scan.ranges.size(); ++i){
//wait until we get to our desired starting angle
if(start_angle < lower_angle_){
start_angle += input_scan.angle_increment;
current_angle += input_scan.angle_increment;
start_time += ros::Duration(input_scan.time_increment);
}
else{
filtered_scan.ranges[count] = input_scan.ranges[i];
if(input_scan.angle_increment > 0){ //if the laserscanner turns counterclockwise
//wait until we get to our desired starting angle
if(start_angle < lower_angle_){
start_angle += input_scan.angle_increment;
current_angle += input_scan.angle_increment;
start_time += ros::Duration(input_scan.time_increment);
}
else{
filtered_scan.ranges[count] = input_scan.ranges[i];

//make sure that we don't update intensity data if its not available
if(input_scan.intensities.size() > i)
filtered_scan.intensities[count] = input_scan.intensities[i];
//make sure that we don't update intensity data if its not available
if(input_scan.intensities.size() > i)
filtered_scan.intensities[count] = input_scan.intensities[i];

count++;
count++;

//check if we need to break out of the loop, basically if the next increment will put us over the threshold
if(current_angle + input_scan.angle_increment > upper_angle_){
break;
//check if we need to break out of the loop, basically if the next increment will put us over the threshold
if(current_angle + input_scan.angle_increment > upper_angle_){
break;
}
current_angle += input_scan.angle_increment;
}
}
else{ //the laserscanner turns clockwise
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a fair amount of repeated code, but in this case I think that is OK - it avoids changing the code for the positive case, so it is unlikely to break anything.

//wait until we get to our desired starting angle
if(start_angle > upper_angle_){
start_angle += input_scan.angle_increment;
current_angle += input_scan.angle_increment;
start_time += ros::Duration(input_scan.time_increment);
}
else{
filtered_scan.ranges[count] = input_scan.ranges[i];

current_angle += input_scan.angle_increment;
//make sure that we don't update intensity data if its not available
if(input_scan.intensities.size() > i)
filtered_scan.intensities[count] = input_scan.intensities[i];

count++;

//check if we need to break out of the loop, basically if the next increment will put us over the threshold
if(current_angle + input_scan.angle_increment < lower_angle_){
break;
}

current_angle += input_scan.angle_increment;

}
}
}

Expand Down