堆栈 Cookie 检测代码检测到基于堆栈的缓冲区溢出

概述

本文讲述了解决报错”堆栈 Cookie 检测代码检测到基于堆栈的缓冲区溢出“的过程

报错情况

0x00007FF7780C4675 处有未经处理的异常(在 control_system.exe 中): 堆栈 Cookie 检测代码检测到基于堆栈的缓冲区溢出。

Release配置下的报错

很不直观,切换到Debug模式下看看

Run-Time Check Failure #2 – Stack around the variable ‘t2’ was corrupted.

Debug配置下的报错

排查

可以看到Debug配置下VS给出了出问题的变量,我们来检查一下


template<typename Derived1, typename Derived2>
void ThreadManager::JacobianT(const Eigen::MatrixBase<Derived1>& q, Eigen::MatrixBase<Derived2>& jacobian_t)
{
	// init objects
	Eigen::Matrix<double, 6, 4> mdh_table;
	Eigen::Isometry3d t1[5];
	Eigen::Isometry3d t2[6];

	// get current mdh_table
	mdh_table = mdh_table_;
	mdh_table.col(2) += q;

	// calculate t_n^(n-1)
	for (int n = 0; n < 6; n++)
	{
		t1[n] = Eigen::AngleAxisd(mdh_table(n, 0), Eigen::Vector3d::UnitX()) *
			Eigen::Translation3d(mdh_table(n, 1), 0, 0) *
			Eigen::AngleAxisd(mdh_table(n, 2), Eigen::Vector3d::UnitZ()) *
			Eigen::Translation3d(0, 0, mdh_table(n, 3));
	}

	// calculate t_n^n
	for (int i = 5; i > -1; i--)
	{
		if (i == 5)
		{
			t2[i].setIdentity();
		}
		else
		{
			t2[i] = t1[i + 1] * t2[i + 1];
		}
	}

	// construct object Jacobian
	for (int i = 0; i < 6; i++)
	{
		jacobian_t(0, i) = t2[i].translation().cross(t2[i].rotation().col(0))(2);
		jacobian_t(1, i) = t2[i].translation().cross(t2[i].rotation().col(1))(2);
		jacobian_t(2, i) = t2[i].translation().cross(t2[i].rotation().col(2))(2);
		jacobian_t(3, i) = t2[i].rotation().col(0)(2);
		jacobian_t(4, i) = t2[i].rotation().col(1)(2);
		jacobian_t(5, i) = t2[i].rotation().col(2)(2);
	}

	return;
}

网上说这个问题是由于存储的内容超出给定的存储空间导致的:参考链接

这里t2[6]的索引是正确的(0~5),不过t1[5]的索引出现了问题(0~5),于是判断是t1的索引超限导致的报错

至于为什么VS给出的是t2内存损坏,可能是跟Eigen中变量的赋值方式有关系,有可能t2在赋值过程中也指向了t1超限的那部分内存,但是这只是个人的推测,坐等高人指点

解决

重新梳理一下函数的逻辑,使用正确的索引即可

发表评论

您的电子邮箱地址不会被公开。 必填项已用 * 标注

此站点使用Akismet来减少垃圾评论。了解我们如何处理您的评论数据