最近想试试ros2,将系统升级成了ubuntu20.04,引发了一大堆新版本的第三方库与旧项目的冲突,果然升级还是要慎重。ros版本也升级为noetic,gozebo也相应地由9.0升级为了11.0,包括gazebo相关的第三方库也随之升级。重新使用uuv_simulator进行仿真时无法工作。重新到github下载源码重新编译。在此简要记录一下遇到的问题。
一、gazebo11与sdformat-9.2问题
sdformat版本升级后,编译器的版本支持也需要做出相应改动。大致会出现如下报错:
/usr/include/sdformat-9.2/sdf/Param.hh:72:57: error: expected constructor, destructor, or type conversion before ‘;’ token template<class T> ParamStreamer(T) -> ParamStreamer<T>; /usr/include/sdformat-9.2/sdf/Param.hh:83:47: error: ‘variant’ is not a member of ‘std’ ParamStreamer<std::variant<Ts...>> sv)
根据error的log定位到uuv_gazebo_plugins的package,在其目录下的CMakeLists.txt中添加对c++17的支持:
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
二、gazebo11与Ignition Math库问题
Ignition Math库相应升级到了v6版本,库内一些类的命名也有所变动,导致编译时出现错误。在此给出v4版本和v6版本的API链接:
V4:https://ignitionrobotics.org/api/math/4.0/namespaceignition_1_1math.html
V6:https://ignitionrobotics.org/api/math/6.7/namespaceignition_1_1math.html
还是在uuv_gazebo_plugins的package中,HydrodynamicModel.cc中计算bounding box调用的类发生了改动,原代码为ignition::math::Box ,新版本更名为 ignition::math::AxisAlignedBox,而新版本的ignition::math::Box是新的实现。需要在BuoyantObject.hh,BuoyantObject.cc,HydrodynamicModel.cc中做出相应修正。
1、对于BuoyantObject.hh:
public: void SetBoundingBox(const ignition::math::Box &_bBox);
...
protected: ignition::math::Box boundingBox;
修改为:
public: void SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox);
...
protected: ignition::math::AxisAlignedBox boundingBox;
2、 对于BuoyantObject.cc:
void BuoyantObject::SetBoundingBox(const ignition::math::Box &_bBox)
{
this->boundingBox = ignition::math::Box(_bBox);
gzmsg << "New bounding box for " << this->link->GetName() << "::"
<< this->boundingBox << std::endl;
}
修改为:
void BuoyantObject::SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox)
{
this->boundingBox = ignition::math::AxisAlignedBox(_bBox);
gzmsg << "New bounding box for " << this->link->GetName() << "::"
<< this->boundingBox << std::endl;
}
3、对于HydrodynamicModel.cc:
// FIXME(mam0box) This is a work around the problem of the invalid bounding
// box returned by Gazebo
if (_sdf->HasElement("box"))
{
sdf::ElementPtr sdfModel = _sdf->GetElement("box");
if (sdfModel->HasElement("width") && sdfModel->HasElement("length") &&
sdfModel->HasElement("height"))
{
double width = sdfModel->Get<double>("width");
double length = sdfModel->Get<double>("length");
double height = sdfModel->Get<double>("height");
ignition::math::Box boundingBox = ignition::math::Box(
ignition::math::Vector3d(-width / 2, -length / 2, -height / 2),
ignition::math::Vector3d(width / 2, length / 2, height / 2));
// Setting the the bounding box from the given dimensions
this->SetBoundingBox(boundingBox);
}
}
修改为:
// FIXME(mam0box) This is a work around the problem of the invalid bounding
// box returned by Gazebo
if (_sdf->HasElement("box"))
{
sdf::ElementPtr sdfModel = _sdf->GetElement("box");
if (sdfModel->HasElement("width") && sdfModel->HasElement("length") &&
sdfModel->HasElement("height"))
{
double width = sdfModel->Get<double>("width");
double length = sdfModel->Get<double>("length");
double height = sdfModel->Get<double>("height");
ignition::math::AxisAlignedBox boundingBox = ignition::math::AxisAlignedBox(
ignition::math::Vector3d(-width / 2, -length / 2, -height / 2),
ignition::math::Vector3d(width / 2, length / 2, height / 2));
// Setting the the bounding box from the given dimensions
this->SetBoundingBox(boundingBox);
}
}
至此,编译顺利通过,仿真运行也没有问题。