carla0.9.14源码编译并添加鱼眼相机补丁
说明
仿真场景的搭建需要鱼眼相机,Carla内置传感器不包括鱼眼相机,网上也找不到carla使用鱼眼相机的例子,找遍carla官网,发现两年前有大佬提供了非官方的鱼眼相机补丁。
注意:
想要使用鱼眼相机需要源码编译Carla,并在编译Carla之前先编译Unreal engine,Unreal engine编译完成大约需要95G的空间,Carla的编译也需要25G的空间,空间小的Ubuntu系统以及不支持显卡的虚拟机无法完成编译。
本文使用的是ubuntu20.04系统,Carla版本为最新的0.9.14版本,Unreal Engine版本为4.26.2。
参考资料:
Carla鱼眼相机补丁链接: https://github.com/carla-simulator/carla/pull/3755。
官方编译文档:https://carla.readthedocs.io/en/latest/build_linux/
carla保姆级编译文章:https://blog.csdn.net/justinyjf/article/details/131200896
一、软件要求
安装依赖:
开始build之前安装二进制文件(cmake、clang、不同版本的Python等)。要安装这些依赖,请运行以下命令:
sudo apt-get update &&
sudo apt-get install wget software-properties-common &&
sudo add-apt-repository ppa:ubuntu-toolchain-r/test &&
wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key|sudo apt-key add
为了避免虚幻引擎和 CARLA 依赖项之间的兼容性问题,请使用相同的编译器版本和 C++ 运行时库来编译所有内容。CARLA 团队使用 clang-8(或 Ubuntu 20.04 中的 clang-10)和 LLVM 的 libc++。
sudo apt-add-repository "deb http://apt.llvm.org/focal/ llvm-toolchain-focal main"
sudo apt-get update
sudo apt-get install build-essential clang-10 lld-10 g++-7 cmake ninja-build libvulkan1 python python-dev python3-dev python3-pip libpng-dev libtiff5-dev libjpeg-dev tzdata sed curl unzip autoconf libtool rsync libxml2-dev git
sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-10/bin/clang++ 180 &&
sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-10/bin/clang 180
安装以下 Python 依赖项:
pip install --user setuptools &&
pip3 install --user -Iv setuptools==47.3.1 &&
pip install --user distro &&
pip3 install --user distro &&
pip install --user wheel &&
pip3 install --user wheel auditwheel
二、unreal engine添加补丁及编译
unreal engine的源码在github是私有仓库,需要在UE4个人中心关联github账号,否则无法搜索到源码。
具体操作参考保姆级教程:https://blog.csdn.net/justinyjf/article/details/131200896
1.关联之后在终端下载unreal engine:
git clone --depth 1 -b carla https://github.com/CarlaUnreal/UnrealEngine.git ~/UnrealEngine_4.26
终端要求输入你的github用户名以及github生成的token密码。
注意:若无法访问github地址的话,开vpn或者早晚人少多试几次,gittee或许也可以(没试过)。
我的vpn有流量限制,就会麻烦很多,先用vpn打开浏览器,在浏览器端下载,开始下载后再关闭vpn,能顺畅的下载下来,下载后解压缩为UnrealEngine_4.26。
2.添加unreal engine补丁
找到补丁文件https://github.com/carla-simulator/carla/files/5739990/UE4_patch_fisheye-sensor.zip,下载zip补丁包,手动将修改后的文件添加上去。
3.编译
cd ~/UnrealEngine_4.26
./Setup.sh
./GenerateProjectFiles.sh
make
cd ~/UnrealEngine_4.26/Engine/Binaries/Linux && ./UE4Editor
由于鱼眼补丁发布的比较早,unreal engine源码后面更新,使用补丁编译过程会出现错误。
error1:/Engine/Source/Runtime/Engine/Private/CubemapUnwrapUtils.cpp,类内未定义GetVertexShader()函数
解决办法:用RHICmdList.GetBoundVertexShader() 代替 GetVertexShader(),例如如下语句替换。
GraphicsPSOInit.BoundShaderState.VertexShaderRHI = VertexShader.GetVertexShader()
GraphicsPSOInit.BoundShaderState.PixelShaderRHI = PixelShader.GetPixelShader()
error2:内存尺寸错误,Engine/Source/Runtime/Core/Private/Serialization/MemoryImage.cpp] [Line: 224]
[FCubemapTexturePropertiesVSFisheye] Calculated Size: 280, Real Size: 288
在对应的Engine/Source/Runtime/Core/Public/Serialization/MemoryImage.h文件中加入私有属性。
解决办法:
private:
LAYOUT_FIELD(uint64, Hash);
LAYOUT_FIELD_EDITORONLY(FHashedNameDebugString, DebugString);
接下来运行一下指令即可
cd ~/UnrealEngine_4.26
./Setup.sh
./GenerateProjectFiles.sh
make
cd ~/UnrealEngine_4.26/Engine/Binaries/Linux && ./UE4Editor
make编译完成:
自动打开UE4Editor编辑界面
到这里unreal engine 编译完成,文件夹大小86G。
三、carla添加补丁及编译
1.下载源码以及更新内容
因为终端下载不了,无法使用git命令,还是去浏览器下载压缩包,下载地址:https://github.com/carla-simulator/carla/releases,下载完压缩包解压缩出来。
接下来更新内容,官方给的命令是运行根目录下的Update.sh脚本,大约需要下载一个10多G的压缩包,能下载的就自动下载安装内容包就好。
./Update.sh
博主因为网络原因终端下载不了,查看Update.sh脚本,选择手动更新内容,去浏览器打开http://carla-assets.s3.amazonaws.com/20221201_5ec9328.tar.gz
手动下载。
下载完毕解压缩,放在下图所示路径下,并且添加一个.version的文件,文件内容为carla的版本0.9.14。
2.设置环境变量
然后设置虚幻引擎安装位置的环境变量,
echo "export UE4_ROOT=~/UnrealEngine_4.26" >> ~/.bashrc
source ~/.bashrc
接下来需要修改/carla-master/Util/BuildTools/Setup.sh脚本中的一些内容,因为sh脚本需要git carla的版本,找到807行直接将其设置为0.9.14。
#CARLA_VERSION=$(get_git_repository_version)
CARLA_VERSION="0.9.14"
log "CARLA version ${CARLA_VERSION}."
3.编译客户端PythonAPI
make PythonAPI
出现boost库不支持C++03编译问题。
实在是不知道那里用到了C++03,猜测是系统默认python版本是3.6,要求是3.8。
渣男式解决:解决不了错误就不让他报错,不显示错误就是没有错误。找到carla-0.9.14/Build/boost-1.80.0-c8-install/include/boost/math/tools /cxx03_warn.hpp。注释掉92行。
使用python3.6,客户端导入carla python库有问题。
换成python3.8,客户端编译成功:
4.编译服务器端
make launch
会报错final修饰的函数无法重写的问题
找到carla-master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h第57行删除final
出现找不到蓝图问题,原因是Unreal/CarlaUE4/content下没有内容。
解决办法:把文件夹直接粘过来。
make launch完成,终端不在变化,进入ue4 editor界面,点击运行。
5.测试鱼眼相机是否添加成功
cd carla-master/PythonAPI/examples
python3 maunaul_control.py
6.发行鱼眼carla预编译版本
如果需要,可以发行鱼眼carla预编译版本,方便移植到其他电脑上,在carla根目录下执行
make package
如果不是直接git下载的carla,会出现git版本的问题,解决方法同上。
接下来就能看见在carla/Dist中生成鱼眼版本carla预编译的压缩包。
导入carla的python库:
python3
import carla
此时会出现libstdc++.so.6的版本错误。
解决办法
sudo apt install libstdc++6
注意:如果是没有安装carla源码编译依赖的机器,上述命令行后不会更新libstdc++6的版本。错误无法消除,需要按照软件要求安装环境,再更新libstdc++6的版本(不知道是因为apt的源的问题还是编译器的问题)。
四、添加鱼眼传感器到Ros bridge
1.carla_ros_bridge功能包下的camera.py添加鱼眼相机类
class FisheyeCamera(Camera):
"""
Camera implementation details for fisheye camera
"""
def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode):
super(
FisheyeCamera, self).__init__(uid=uid,
name=name,
parent=parent,
relative_spawn_pose=relative_spawn_pose,
node=node,
synchronous_mode=synchronous_mode,
carla_actor=carla_actor)
self.listen()
def get_carla_image_data_array(self, carla_image):
carla_image_data_array = numpy.ndarray(shape=(carla_image.height, carla_image.width, 4),
dtype=numpy.uint8, buffer=carla_image.raw_data)
return carla_image_data_array, 'bgra8'
设置相机内参camera_info的话题,因为鱼眼相机参数不同于普通相机的参数名,所以要修改才能编译通过。
if self.__class__.__name__ == "FisheyeCamera":
camera_info.width = int(self.carla_actor.attributes['x_size'])
camera_info.height = int(self.carla_actor.attributes['y_size'])
camera_info.distortion_model = 'plumb_bob'
cx = float(self.carla_actor.attributes['c_x'])
cy = float(self.carla_actor.attributes['c_y'])
fx = float(self.carla_actor.attributes['f_x'])
fy = float(self.carla_actor.attributes['f_y'])
else:
camera_info.width = int(self.carla_actor.attributes['image_size_x'])
camera_info.height = int(self.carla_actor.attributes['image_size_y'])
camera_info.distortion_model = 'plumb_bob'
cx = camera_info.width / 2.0
cy = camera_info.height / 2.0
fx = camera_info.width / (
2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0))
fy = fx
2.actor_factory.py中导入鱼眼相机类。
from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera,FisheyeCamera
创建模型与初始化鱼眼相机类,发布carla/ego_vehicle/fisheye/image的话题topic。
elif carla_actor.type_id.startswith("sensor.camera.fisheye"):
actor = FisheyeCamera(uid, name, parent, spawn_pose, self.node,
carla_actor, self.sync_mode)
3.相机绑定车辆
spawn_actor功能包中,依附于vehicle模型,object.json加入四个鱼眼相机模型,以下是左相机的内外参数。
{
"type": "sensor.camera.fisheye",
"id": "fisheye_left",
"spawn_point": {"x": 0.0, "y": 1.05, "z": 1.05, "roll": 0.0, "pitch": 30.0, "yaw": 90.0},
"x_size": 960,
"y_size": 640,
"max_angle": 190,
"d_1": -3.5510560636666778e-02,
"d_2": -1.9848228876245811e-02,
"d_3": 2.6080053057044101e-02,
"d_4": -9.7183762742328750e-03,
"f_x": 3.0334009006384287e+02,
"f_y": 3.2229678244636966e+02,
"c_x": 4.8649280066241465e+02,
"c_y": 3.2388095214561167e+02
},
4.查看图像
ros2 启动手动控制节点,查看topiclist可以看到鱼眼相机的话题发布。
创建鱼眼相机话题订阅者
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr fisheye_left_subscriber;
fisheye_left_subscriber = this->create_subscription<sensor_msgs::msg::Image>("/carla/ego_vehicle/fisheye_left/image", 10, std::bind(&BevNode::FisheyeleftCallback, this, _1));
订阅话题的回调函数,opencv显示及保存图像。使用cv_bridge可以直接将ros中的传感器图像信息进行转换。
void FisheyeleftCallback(const sensor_msgs::msg::Image::SharedPtr msg)
{
RCLCPP_INFO(LOGGER, "recieve fisheye_left_camera frame");
try {
// 将ROS图像消息转换为OpenCV图像
cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
// 显示图像
cv::imshow("fisheye", cv_ptr->image);
cv::waitKey(1); // 刷新显示
// 保存图像
if (cv::waitKey(1) == 's') {
// 保存图像
cv::imwrite("output_image1.jpg", cv_ptr->image);
RCLCPP_INFO(this->get_logger(), "Image saved.");
}
}
catch (cv_bridge::Exception& e) {
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
}
}
得到鱼眼相机拍摄图像
至此,鱼眼相机在carla-ros-bridge中编译完成。
在后续的测试中,鱼眼相机在carla-ros-bridge导出数据的帧率大约是普通相机的一半,四个鱼眼相机在3090卡上仅有10帧左右帧率。大佬如果有在carla-ros-bridge提高鱼眼或多相机帧率的方法,请私我一下,不胜感激。