Skip to content

Commit

Permalink
Fix Eigen crash of memory alignment
Browse files Browse the repository at this point in the history
#0  0xb29183ee in ?? () from /lib/libc.so.6
iralabdisco#1  0x080c85a2 in Eigen::internal::handmade_aligned_free(void*) ()
iralabdisco#2  0x080c85ef in Eigen::internal::aligned_free(void*) ()
iralabdisco#3  0x080cf4d8 in void Eigen::internal::conditional_aligned_free<true>(void*) ()
iralabdisco#4  0x080d5a6f in void Eigen::internal::conditional_aligned_delete_auto<float, true>(float*, unsigned int) ()
iralabdisco#5  0x080d350e in Eigen::DenseStorage<float, -1, -1, -1, 0>::~DenseStorage() ()
iralabdisco#6  0x080ce018 in Eigen::PlainObjectBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> >::~PlainObjectBase() ()
iralabdisco#7  0x080ce030 in Eigen::Matrix<float, -1, -1, 0, -1, -1>::~Matrix() ()
iralabdisco#8  0x080c4a65 in LaserscanMerger::scanCallback(boost::shared_ptr<sensor_msgs::LaserScan_<std::allocator<void> > const> const&, std::string) ()
  • Loading branch information
awesomebytes committed Jun 20, 2017
1 parent e6a4c1e commit b9ff953
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion launch/laserscan_multi_merger.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
angle_max: 2.36
angle_min: -2.36
cloud_destination_topic: /merged_cloud
destination_frame: /base_footprint
destination_frame: base_footprint
laserscan_topics: /scan /pepper/laser
range_max: 4.0
range_min: 0.2
Expand Down
2 changes: 1 addition & 1 deletion src/laserscan_multi_merger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ class LaserscanMerger
string cloud_destination_topic;
string scan_destination_topic;
vector<string> laserscan_topics;
Eigen::MatrixXf points;
};

void LaserscanMerger::reconfigureCallback(laserscan_multi_mergerConfig &config, uint32_t level)
Expand Down Expand Up @@ -184,7 +185,6 @@ void LaserscanMerger::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan,

point_cloud_publisher_.publish(merged_cloud);

Eigen::MatrixXf points;
getPointCloudAsEigen(merged_cloud,points);

pointcloud_to_laserscan(points, &merged_cloud);
Expand Down

0 comments on commit b9ff953

Please sign in to comment.