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

Improving performance for ARM7-based platforms #18

Open
wants to merge 3 commits into
base: indigo-devel
Choose a base branch
from

Conversation

dkargin
Copy link

@dkargin dkargin commented Dec 20, 2016

  • most calculations use float instead of double (for NEON instruction set)
  • column-order calculation, less 'atan2' calls
  • added tests for performance comparison. 20x faster so far (tests were not so reliable)
  • added test node to compare both scans from old and new processor

- most calculations use float instead of double
- column-order calculation, less 'atan2' calls
- added tests for perfomance comparison. 20x faster so far (tests were not so reialble)
- added test node to compare both scans from old and new processor
Copy link

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

Thanks this looks like a good improvement. I have reviewed the API and it looks like a good change. I have not had a chance to test or review the implementation.

@@ -64,8 +64,45 @@ namespace depthimage_to_laserscan
*
*/
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr& depth_msg,
Copy link

Choose a reason for hiding this comment

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

inline needed due to implementation in the header?

Copy link
Author

Choose a reason for hiding this comment

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

Moved implementation to cpp. Only template part is left in header

* @return sensor_msgs::LaserScanPtr for the center row(s) of the depth image.
*
*/
sensor_msgs::LaserScanPtr convert_msg_f(const sensor_msgs::ImageConstPtr& depth_msg,
Copy link

Choose a reason for hiding this comment

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

Inline here too. But I'd suggest that we don't need to add the wrapper on the allocation free conversion. Passing in the message is a cleaner API. And for the double one, it's important to keep it available for backwards compatibility, but since this is a new API we don't need to add the parallel interface.

@@ -102,7 +118,7 @@ sensor_msgs::LaserScanPtr DepthImageToLaserScan::convert_msg(const sensor_msgs::
double angle_min = -angle_between_rays(center_ray, right_ray); // Negative because the laserscan message expects an opposite rotation of that from the depth image

// Fill in laserscan message
sensor_msgs::LaserScanPtr scan_msg(new sensor_msgs::LaserScan());
//sensor_msgs::LaserScanPtr scan_msg(new sensor_msgs::LaserScan());
Copy link

Choose a reason for hiding this comment

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

Please delete the old code instead of just commenting it.

@@ -184,7 +245,8 @@ namespace depthimage_to_laserscan
int offset = (int)(cam_model.cy()-scan_height/2);
depth_row += offset*row_step; // Offset to center of image

for(int v = offset; v < offset+scan_height_; v++, depth_row += row_step){
for(int v = offset; v < offset+scan_height_; v++, depth_row += row_step)
{
Copy link

Choose a reason for hiding this comment

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

Please avoid whitespace changes only to keep merges as easy as possible. I won't object to the newlines being inserted, but there are a few other lines with this rewrapping of unchanged lines which makes the review harder.

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.

2 participants