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

Fixes #341 #345

Merged
merged 1 commit into from
Aug 3, 2018
Merged

Fixes #341 #345

merged 1 commit into from
Aug 3, 2018

Conversation

oceanusxiv
Copy link
Contributor

@oceanusxiv oceanusxiv commented Jul 30, 2018

This pull request is in regards to #341

After filing the bug report I went an did some digging to figure out why the bug was occurring.
As it turns out, in laser_scan_display:75, the function call:

    projector_->transformLaserScanToPointCloud(
      fixed_frame_.toStdString(),
      *scan,
      *cloud,
      *buffer,
      laser_geometry::channel_option::Intensity);

calls a function in laser_geometry with a prototype as such:

  void transformLaserScanToPointCloud(
    const std::string & target_frame,
    const sensor_msgs::msg::LaserScan & scan_in,
    sensor_msgs::msg::PointCloud2 & cloud_out,
    tf2::BufferCore & tf,
    double range_cutoff = -1.0,
    int channel_options = channel_option::Default)

The relevant parameter here is the range_cutoff, which controls at what range reading the transform should discard the readings. By default this value is implicitly set to -1 as seen, which means the range_cutoff would be inherited from the max_range of the incoming Laserscan, this is usually desired behavior.

However, range_cutoff is not the only default argument, channel_options is one as well, and the bug was caused by ambigious interpretation of the arguments due to the original call above omitting the range_cutoff. Since both arguments can be implicitly converted to one another's type, both are default, and range_cutoff comes first, this results in the interpretation that

range_cutoff = laser_geometry::channel_option::Intensity

cutoff is one meter because laser_geometry::channel_option::Intensity = 0x01

The proposed fix is the simplest possible solution, which is to explicitly set range_cutoff and correct the positioning.

@esteve esteve added the in review Waiting for review (Kanban column) label Jul 30, 2018
@MarcTestier
Copy link

MarcTestier commented Jul 31, 2018

Indeed, the problem is that ROS 1 LaserProjection class has multiple definitions of the transformLaserScanToPointCloud function as seen here :

whereas the ROS 2 LaserProjection class only propose one :
void transformLaserScanToPointCloud( const std::string & target_frame, const sensor_msgs::msg::LaserScan & scan_in, sensor_msgs::msg::PointCloud2 & cloud_out, tf2::BufferCore & tf, double range_cutoff = -1.0, int channel_options = channel_option::Default)

Another solution would be that the ROS 2 LaserProjection class propose multiple definitions of transformLaserScanToPointCloud just like ROS 1. That would avoid other potential conflict like this one.

@mjcarroll
Copy link
Member

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@mjcarroll
Copy link
Member

Confirmed that the behavior exists and that this fixes it, so LGTM.

@mjcarroll mjcarroll merged commit 6779e30 into ros2:ros2 Aug 3, 2018
@mjcarroll mjcarroll removed the in review Waiting for review (Kanban column) label Aug 3, 2018
@sloretz sloretz mentioned this pull request Aug 16, 2018
12 tasks
wjwwood pushed a commit that referenced this pull request Aug 20, 2018
wjwwood added a commit that referenced this pull request Aug 20, 2018
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants