国产 无码 综合区,色欲AV无码国产永久播放,无码天堂亚洲国产AV,国产日韩欧美女同一区二区

Cartographer算法2D激光雷達(dá)與IMU融合建圖 首先先說一下我的硬件設(shè)備:

這篇具有很好參考價(jià)值的文章主要介紹了Cartographer算法2D激光雷達(dá)與IMU融合建圖 首先先說一下我的硬件設(shè)備:。希望對(duì)大家有所幫助。如果存在錯(cuò)誤或未考慮完全的地方,請(qǐng)大家不吝賜教,您也可以點(diǎn)擊"舉報(bào)違法"按鈕提交疑問。

?上一篇文章講了cartographer算法手持雷達(dá)建圖的參數(shù)調(diào)試,這篇進(jìn)一步講如何融合2D雷達(dá)與IMU采用cartographer算法進(jìn)行slam建圖。

cartographer算法手持二維激光雷達(dá)建圖(不使用里程計(jì)及IMU)

https://blog.csdn.net/wangchuchua/article/details/127268037?spm=1001.2014.3001.5502

首先先說一下我的硬件設(shè)備:

思嵐s1激光雷達(dá)、Tobotics ROS IMU HFI-A9。

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

??和上一篇講的一樣在進(jìn)行文件修改之前一定一定要先弄明白自己的雷達(dá)和IMU的話題名稱topic_id以及frame_id,否則名稱對(duì)不上肯定是會(huì)報(bào)錯(cuò)的。

首先啟動(dòng)雷達(dá),如果有用思嵐激光雷達(dá)的小伙伴可以參考這個(gè)網(wǎng)址。(只要可以實(shí)現(xiàn)點(diǎn)云信息的發(fā)布就好。)ROS與激光雷達(dá)入門教程-ROS中使用激光雷達(dá)(思嵐S1) - 創(chuàng)客智造

雷達(dá)的frame_id就是圖中畫紅圈的,我的是laser。

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:??接下來就是查看雷達(dá)的話題名稱,打開終端輸入:

rostopic list

可以看到雷達(dá)topic名稱一般都是scan。同時(shí)還有另一種方法查詢雷達(dá)的frame_id,就是在終端輸入:

rostopic echo /topic | grep frame_id

其中topic名稱輸入你雷達(dá)的話題名稱就可,我的話題名稱是scan所以輸入:

rostopic echo /scan | grep frame_id

?這樣就能查到話題scan的fram_id啦。通過以上操作我得知了我的雷達(dá)話題是scan、frame_id是laser。

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

?好接下來啟動(dòng)IMU模塊,一般rosIMU是會(huì)有啟動(dòng)包的,啟動(dòng)IMU后通過rostopic查詢一下IMU的話題名稱,我的話題名稱是/imu。知道話題名稱后輸入命令:rostopic echo /imu?| grep frame_id查詢frame-id。通過以上操作我得知了我IMU的話題名稱是/imu,frame-id是base_link。知道這些后就開始正式的修改相關(guān)的文件。

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

首先找到~/google_ws/src/cartographer_ros/cartographer_ros/configuration_files目錄下的建立一個(gè)revo_lds.lua文件,為了和手持建圖的lua文件區(qū)分開,我有復(fù)制了這個(gè)文件,重命名為revo_imu.lua。修改后文件內(nèi)容如下:

-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
--      http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "base_link",
  published_frame = "laser",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = false,
  use_pose_extrapolator = true,
  use_odometry = false,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1

POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65

return options

主要修改的點(diǎn)就是一下三個(gè)地方:

tracking_frame = "base_link",#這里要與imu的frame_id名稱一致
published_frame = "laser",#這里要與雷達(dá)的frame_id名稱一致
TRAJECTORY_BUILDER_2D.use_imu_data = true

然后在~/google_ws/src/cartographer_ros/cartographer_ros//urdf/文件下創(chuàng)建一個(gè)urdf文件文件內(nèi)容如下所示(我的urdf文件名稱是:backpack_2d1.urdf,原本包里自帶了兩個(gè)urdf文件因?yàn)槲乙约赫{(diào)整imu和雷達(dá)的位置關(guān)系就另寫了一個(gè)urdf文件):這里一定要注意urdf里的link name一定要與雷達(dá)或者imu的fram_id相對(duì)應(yīng)。

<!--
  Copyright 2016 The Cartographer Authors

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

       http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->
<robot name="mini">
  <material name="orange">
    <color rgba="1.0 0.5 0.2 1" />
  </material>
  <material name="gray">
    <color rgba="0.2 0.2 0.2 1" />
  </material>

  <link name="base_link">#與imu的fram_id對(duì)應(yīng)
    <visual>
      <origin xyz="0 0 0" />
      <geometry>
        <box size="0.06 0.04 0.02" />
      </geometry>
      <material name="orange" />
    </visual>
  </link>
  <link name="laser">#與雷達(dá)的fram_id對(duì)應(yīng)
    <visual>
      <origin xyz="0 0 0" />
      <geometry>
        <cylinder length="0.05" radius="0.03" />
      </geometry>
      <material name="gray" />
    </visual>
  </link>


  <joint name="imu2laser" type="fixed">
    <parent link="laser" />
    <child link="base_link" />
    <origin xyz="0 0 -0.035" />
  </joint>

</robot>

?在riviz中顯示是這樣的,小老板們可以根據(jù)需要調(diào)整雷達(dá)和imu之間的相對(duì)位置關(guān)系。Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

在~/google_ws/src/cartographer_ros/cartographer_ros/launch目錄下建立launch文件,我的文件名稱是demo_revo_sc_imu.launch。文件內(nèi)容如下:

<!--
  Copyright 2016 The Cartographer Authors

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

       http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->

<launch>
  <param name="/use_sim_time" value="false" />

  <node name="rplidarNode"          pkg="rplidar_ros"  type="rplidarNode" output="screen">
  <param name="serial_port"         type="string" value="/dev/ttyUSB0"/>  
  <param name="serial_baudrate"     type="int"    value="256000"/>
  <param name="frame_id"            type="string" value="laser"/>
  <param name="inverted"            type="bool"   value="false"/>
  <param name="angle_compensate"    type="bool"   value="true"/>
  </node>

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename revo_imu.lua"
      output="screen">
    <remap from="scan" to="scan" />
    <remap from="imu/data" to="imu" />#這里是你的imu的話題名稱
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  <param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />


  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
 
</launch>

這個(gè)文件中包含了啟動(dòng)雷達(dá)節(jié)點(diǎn),和cartographer建圖節(jié)點(diǎn),相對(duì)于上節(jié)的launch文件內(nèi)容增加了?

?<remap from="imu/data" to="imu" />注意要用你自己imu的話題名稱。

以及 urdf文件,注意要對(duì)應(yīng)你的urdf文件路徑。

 <param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

到這里文件調(diào)整部分就完成了,可以開始啟動(dòng)建圖了,因?yàn)樯厦娴膌aunch文件沒有包含imu啟動(dòng)節(jié)點(diǎn)所以我這里先單獨(dú)啟動(dòng)imu。?

roslaunch handsfree_ros_imu imu1.launch

imu啟動(dòng)之后就可以運(yùn)行?demo_revo_sc_imu.launch文件了,別忘記啟動(dòng)之前要catkin_make_isolated --install --use-ninja。

source install_isolated/setup.bash
catkin_make_isolated --install --use-ninja
roslaunch cartographer_ros demo_revo_sc_imu.launch

?運(yùn)行成功后的效果是這樣的。Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

?打開終端輸入rqt_graph查看節(jié)點(diǎn)關(guān)系,我們可以看到imu和雷達(dá)信息已經(jīng)輸入到cartographer的節(jié)點(diǎn)中去說明融合成功了。

rqt_graph

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

打開終端輸入rosrun rqt_tf_tree rqt_tf_tree得到tf關(guān)系圖:?

Cartographer算法2D激光雷達(dá)與IMU融合建圖
                    
            
首先先說一下我的硬件設(shè)備:

到這里就完成了cartographer算法的雷達(dá)與IMU融合建圖。希望這篇文章能夠幫助到大家,祝大家生活愉快,學(xué)業(yè)順利 (*^▽^*)。文章來源地址http://www.zghlxwxcb.cn/news/detail-409304.html

到了這里,關(guān)于Cartographer算法2D激光雷達(dá)與IMU融合建圖 首先先說一下我的硬件設(shè)備:的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!

本文來自互聯(lián)網(wǎng)用戶投稿,該文觀點(diǎn)僅代表作者本人,不代表本站立場(chǎng)。本站僅提供信息存儲(chǔ)空間服務(wù),不擁有所有權(quán),不承擔(dān)相關(guān)法律責(zé)任。如若轉(zhuǎn)載,請(qǐng)注明出處: 如若內(nèi)容造成侵權(quán)/違法違規(guī)/事實(shí)不符,請(qǐng)點(diǎn)擊違法舉報(bào)進(jìn)行投訴反饋,一經(jīng)查實(shí),立即刪除!

領(lǐng)支付寶紅包贊助服務(wù)器費(fèi)用

相關(guān)文章

  • 3D激光SLAM:LeGO-LOAM論文解讀---激光雷達(dá)里程計(jì)與建圖

    3D激光SLAM:LeGO-LOAM論文解讀---激光雷達(dá)里程計(jì)與建圖

    激光雷達(dá)里程計(jì)模塊的功能就是 :估計(jì)相鄰幀之間的位姿變換。 估計(jì)的方式 :在相鄰幀之間做點(diǎn)到線的約束和點(diǎn)到面的約束 具體的方式和LOAM一樣 針對(duì)LOAM的改進(jìn) 1 基于標(biāo)簽的匹配 在特征提取部分提取的特征點(diǎn)都會(huì)有個(gè)標(biāo)簽(在點(diǎn)云分割時(shí)分配的) 因此在找對(duì)應(yīng)點(diǎn)時(shí),標(biāo)簽

    2023年04月09日
    瀏覽(28)
  • 鐳神智能N10激光雷達(dá)測(cè)評(píng)+ROS_Cartographer應(yīng)用測(cè)試

    鐳神智能N10激光雷達(dá)測(cè)評(píng)+ROS_Cartographer應(yīng)用測(cè)試

    ??將N10雷達(dá)連接ROS主控(本次使用Nvidia Jetson nano+melodic系統(tǒng)進(jìn)行測(cè)試),通過Ubuntu電腦或虛擬機(jī)查看構(gòu)建好的地圖。 ??N10雷達(dá)的掃描頻率為 6~12HZ的可調(diào)區(qū)間 ,對(duì)應(yīng)可實(shí)現(xiàn) 0.48°~0.96°的角度分辨率,N10采用TOF的測(cè)距技術(shù),每秒4500次的高速激光測(cè)距采樣能力,可以在25米半徑

    2024年02月16日
    瀏覽(191)
  • 使用lidar_align進(jìn)行激光雷達(dá)與IMU的外參標(biāo)定(超詳細(xì)教程)

    使用lidar_align進(jìn)行激光雷達(dá)與IMU的外參標(biāo)定(超詳細(xì)教程)

    1、下載lidar_align源碼 ethz-asl/lidar_align: A simple method for finding the extrinsic calibration between a 3D lidar and a 6-dof pose sensor (github.com) https://github.com/ethz-asl/lidar_align 2、解壓到ros工作空間目錄下的src文件中 不知道如何創(chuàng)建ros工作空間的可以參考我另一篇博客: ubuntu下如何創(chuàng)建ros工作空間

    2024年02月08日
    瀏覽(31)
  • 3D激光雷達(dá)和相機(jī)融合

    3D激光雷達(dá)和相機(jī)融合

    主要看重投影誤差,cv的標(biāo)定識(shí)別率也太低了。。。原因是找到了,相機(jī)給的曝光時(shí)間5ms,增大曝光時(shí)間成功率大大提升,但曝光時(shí)間給打了,影響實(shí)時(shí)性,頭疼。。 主要是3D-2D的標(biāo)定 采集標(biāo)定數(shù)據(jù) 參照以下采集標(biāo)定數(shù)據(jù)和處理標(biāo)定數(shù)據(jù),pcd角點(diǎn)選取和圖像角點(diǎn)選?。?https:

    2024年02月06日
    瀏覽(95)
  • 深度相機(jī)和激光雷達(dá)的融合標(biāo)定(Autoware)

    深度相機(jī)和激光雷達(dá)的融合標(biāo)定(Autoware)

    深度相機(jī)和激光雷達(dá)是智能汽車上常用的傳感器。但深度相機(jī)具有特征難以提取,容易受到視角影響。激光雷達(dá)存在數(shù)據(jù)不夠直觀且容易被吸收,從而丟失信息。因此在自動(dòng)駕駛領(lǐng)域,需要對(duì)于不同傳感器做數(shù)據(jù)的融合和傳感器的標(biāo)定。 內(nèi)參標(biāo)定的原理和方法比較簡(jiǎn)單,由于

    2024年02月10日
    瀏覽(87)
  • 視覺與激光雷達(dá)融合3D檢測(cè)(一)AVOD

    視覺與激光雷達(dá)融合3D檢測(cè)(一)AVOD

    AVOD(Aggregate View Object Detection)和MV3D類似,是一種融合3維點(diǎn)云和相機(jī)RGB圖像的三維目標(biāo)檢測(cè)算法. 不同的是: MV3D中融合了相機(jī)RGB圖像,點(diǎn)云BEV映射和FrontView映射,而AVOD則只融合相機(jī)RGB圖像和點(diǎn)云BEV映射. ? ? ? ? 從網(wǎng)絡(luò)結(jié)果來看,AVOD采用了基于兩階的檢測(cè)網(wǎng)絡(luò),這讓我們很容易想到

    2024年02月07日
    瀏覽(568)
  • 傳感器融合 | 適用于自動(dòng)駕駛場(chǎng)景的激光雷達(dá)傳感器融合項(xiàng)目_將激光雷達(dá)的高分辨率成像+測(cè)量物體速度的能力相結(jié)合

    傳感器融合 | 適用于自動(dòng)駕駛場(chǎng)景的激光雷達(dá)傳感器融合項(xiàng)目_將激光雷達(dá)的高分辨率成像+測(cè)量物體速度的能力相結(jié)合

    項(xiàng)目應(yīng)用場(chǎng)景 面向自動(dòng)駕駛場(chǎng)景的激光雷達(dá)傳感器融合,將激光雷達(dá)的高分辨率成像+測(cè)量物體速度的能力相結(jié)合,項(xiàng)目是一個(gè)從多個(gè)傳感器獲取數(shù)據(jù)并將其組合起來的過程,可以更加好地進(jìn)行環(huán)境感知。項(xiàng)目支持 ubuntu、mac 和 windows 平臺(tái)。 項(xiàng)目效果 項(xiàng)目細(xì)節(jié) == 具體參見項(xiàng)目

    2024年04月24日
    瀏覽(103)
  • Autoware1.14-攝像頭、激光雷達(dá)感知融合

    Autoware1.14-攝像頭、激光雷達(dá)感知融合

    實(shí)現(xiàn)目標(biāo): 利用攝像頭目標(biāo)檢測(cè)結(jié)果 vision_darknet_yolo3 (人、車)、利用激光雷達(dá)獲得目標(biāo)的幾何信息 lidar_euclidean_cluster_detect (大小、距離)、利用感知融合模塊融合攝像頭和激光雷達(dá)信息 range_vision_fusion ,并在三維地圖中可視化。 效果展示: 激光雷達(dá)-攝像頭感知融合展示

    2024年02月05日
    瀏覽(93)
  • 使用擴(kuò)展卡爾曼濾波(EKF)融合激光雷達(dá)和雷達(dá)數(shù)據(jù)(Matlab代碼實(shí)現(xiàn))

    使用擴(kuò)展卡爾曼濾波(EKF)融合激光雷達(dá)和雷達(dá)數(shù)據(jù)(Matlab代碼實(shí)現(xiàn))

    ???????? 歡迎來到本博客 ???????? ??博主優(yōu)勢(shì): ?????? 博客內(nèi)容盡量做到思維縝密,邏輯清晰,為了方便讀者。 ?? 座右銘: 行百里者,半于九十。 ?????? 本文目錄如下: ?????? 目錄 ??1 概述 ??2 運(yùn)行結(jié)果 ??3 參考文獻(xiàn) ??4 Matlab代碼實(shí)現(xiàn) 大多數(shù)自

    2024年02月09日
    瀏覽(89)
  • Fusion_PointClouds - 多激光雷達(dá)點(diǎn)云數(shù)據(jù)融合

    Fusion_PointClouds - 多激光雷達(dá)點(diǎn)云數(shù)據(jù)融合

    fusion_pointclouds 主要目的為Ubuntu環(huán)境下無人車多激光雷達(dá)標(biāo)定之后, 將多個(gè)激光雷達(dá)點(diǎn)云話題/坐標(biāo)系 通過PCL (Point Cloud Library)融合為 一個(gè)ros點(diǎn)云話題,以便于后期點(diǎn)云地面分割與地面處理等等。 1.1 應(yīng)用場(chǎng)景 圖1:為了保證激光雷達(dá)的360°環(huán)境覆蓋,我們需要用到多傳感器的拼

    2024年02月03日
    瀏覽(97)

覺得文章有用就打賞一下文章作者

支付寶掃一掃打賞

博客贊助

微信掃一掃打賞

請(qǐng)作者喝杯咖啡吧~博客贊助

支付寶掃一掃領(lǐng)取紅包,優(yōu)惠每天領(lǐng)

二維碼1

領(lǐng)取紅包

二維碼2

領(lǐng)紅包