YdLidar
运行官方例程ydlidar_sample
增加当前用户的操作权限
将YdLidar插入USB口后,会在/dev/目录下生成/dev/ttyUSB0文件(也可能为/dev/ttyUSB1,/dev/ttyUSB2...),
查看此文件
ls -l /dev/ttyUSB0
输出为:
crw-rw---- 1 root dialout 188 , ttyUSB0
c说明表明设备为字符设备文件(d表示目录文件,-表示普通文件,l表示链接文件,b表示块文件),
其中rw-rw----表示root用户作为文件所有者可以读和写,dialout用户组内的用户可以读和写,其他用户不允许读、写和执行(r表示可读,w表示可写,x表示可执行)
因此,需要将当前用户增加到dialout用户组中
sudo usermod -a -G dialout yottayuan
构建ydlidar_sample程序
进入isaacSDK\packages\ydlidar\apps目录下执行:
bazel build ydlidar_sample
运行ydlidar_sample程序
进入isaacSDK\packages\ydlidar\apps目录下执行:
bazel run ydlidar_sample
packages/ydlidar/apps/BUILD
查看BUILD文件,可知,程序引用了ydlidar组件
load("//engine/build:isaac.bzl", "isaac_app")
isaac_app(
name = "ydlidar_sample",
modules = [
"ydlidar",
],
)
packages/ydlidar/apps/
{
"name": "ydlidar_sample",
"modules": [
"ydlidar"
],
"config": {
"lidar": {
"yd_lidar_driver": {
"device": "/dev/ttyUSB0"
}
},
"websight": {
"WebsightServer": {
"ui_config": {
"windows": {
"YDLidar: Samples Per Tick": {
"renderer": "plot",
"dims": {
"width": 1024,
"height": 200
},
"channels": [
{ "name" : "ydlidar_sample/ydlidar/driver/samples_count" },
{ "name" : "ydlidar_sample/ydlidar/driver/arc_measured" }
]
}
}
}
}
}
},
"graph": {
"nodes": [
{
"name": "ydlidar",
"components": [
{
"name": "message_ledger",
"type": "isaac::alice::MessageLedger"
},
{
"name": "driver",
"type": "isaac::ydlidar::YdLidar"
}
]
}
],
"edges": [
]
}
}
isaac.ydlidar.YdLidar
Description
YDLidar X4 is alow cost LIDAR that is popular with hobbyist.
Type: Codelet - This component ticks either periodically or when it receives messages.
Incoming messages
(none)
Outgoing messages
- flatscan [FlatscanProto]: A flat scan from the LIDAR Average message covers about 0.4 radians and contains 40 measurements Average message publish rate is 120 messages per second
Parameters
- device [string] [default=”/dev/ttyUSB0”]: Serial port where device is connected
FlatscanProto
# A 2D range scan which is essentially a flat version of the 3D RangeScanProto
struct FlatscanProto {
# Angles (in radians) under which rays are shot
angles @0: List(Float32);
# Return distance of the ray
ranges @1: List(Float32);
# Beams with a range smaller than or equal to this distance are considered to have returned an
# invalid measurement.
invalidRangeThreshold @2: Float64;
# Beams with a range larger than or equal to this distance are considered to not have hit an
# obstacle within the maximum possible range of the sensor.
outOfRangeThreshold @3: Float64;
# Return the visibility of a given ray (the longest valid distance of a beams in this direction)
# This field is optional, however if it is set, it must have the same size as ranges and angles.
visibilities @4: List(Float32);
}
isaac.flatsim.SimRangeScan
Description
Simulates a 2D range scan
Type: Codelet - This component ticks either periodically or when it receives messages.
Incoming messages
(none)
Outgoing messages
- flatscan [FlatscanProto]: Output a FlatScan proto: this is a list of beams (angle + distance)
Parameters
- num_beams [int] [default=360]: The number of beams in the range scan
- min_range [double] [default=0.25]: The minimum range at which obstacles are detected
- max_range [double] [default=50.0]: The maximum range of the simulated LIDAR
- min_angle [double] [default=0.0]: The min angle of simulated beams
- max_angle [double] [default=TwoPi<double>]: The max angle of simulated beams
- map [string] [default=”map”]: Map node to use for tracing range scans
isaac.lidar_slam.GMapping
Description
This component wraps the GMapping LIDAR SLAM library for ISAAC SDK. You can learn more about GMapping on their webpage: https://openslam-org.github.io/gmapping.html. Please note that GMapping is an experimental library and that results may vary depending on the LIDAR you are using or the environment you are trying to map.
Type: Codelet - This component ticks either periodically or when it receives messages.
Incoming messages
- flatscan [FlatscanProto]: GMapping uses a 2D LIDAR scan to build the map
- odometry [Odometry2Proto]: Odometry can either be read from this message or from the pose tree. The message is only used if the parameter <cite style="box-sizing: border-box;">use_pose_tree</cite> is set to false, otherwise odometry is read from the pose tree.
Outgoing messages
(none)
Parameters
- file_path [string] [default=”/tmp”]: Directory path used to save map snapshots
- build_map_period [double] [default=2.0]: How often the map is recomputed, in seconds
- laser_matcher_resolution [double] [default=DegToRad(3.0)]: Resolution to be used in scan matcher angles
- map_x_max [double] [default=100.]: Maximum x value of the initial map
- map_y_max [double] [default=100.]: Maximum y value of the initial map
- map_x_min [double] [default=-100.]: Minimum x value of the initial map
- map_y_min [double] [default=-100.]: Minimum y value of the initial map
- map_resolution [double] [default=0.1]: Distance between each pixel in the map
- max_range [double] [default=32.0]: The maximum range of the lidar. This value should be close to the physical range of the lidar to exploit as much of the available information. This value must not be larger than the range of lidar for GMapping to operate.
- map_update_range [double] [default=30.0]: The range within which the map is updated. The update range must be smaller or equal to the maximum range parameter as it relies on the lidar range information. The value chosen allows the tradeoff between the map global consistency and its sharpness.
- number_particles [int] [default=40]: Number of particles used to estimate position of the robot
- linear_distance [double] [default=0.3]: Linear threshold used to attempt scan matching
- angular_distance [double] [default=0.1]: Angular threshold used to attempt scan matching
- use_pose_tree [bool] [default=false]: Whether robot pose is read from pose tree or RX channel
isaac.lidar_slam.Cartographer
Description
This component wraps the Google Cartographer LIDAR SLAM library for ISAAC SDK. You can learn more about Cartographer on their webpage: https://google-cartographer.readthedocs.io/en/latest/. Please note that Cartographer is an experimental library and that results may vary depending on the LIDAR you are using or the environment you are trying to map.
Type: Codelet - This component ticks either periodically or when it receives messages.
Incoming messages
- flatscan [FlatscanProto]: Cartographer uses a 2D LIDAR scan to build the map
Outgoing messages
(none)
Parameters
- lua_configuration_directory [string] [default=”“]: Folders to search for Cartographer lua scripts, separated by comma
- lua_configuration_basename [string] [default=”“]: File name of the specific Cartographer lua script to load
- output_path [string] [default=”/tmp”]: Folder to write submaps and generated map
- background_size [Vector2i] [default=Vector2i(1500, 1500)]: The size of the canvas for visualizing the map in sight (in grid cells)
- background_translation [Vector2d] [default=Vector2d(-75, -75)]: Translation to apply on background image (in meters)
- num_visible_submaps [int] [default=8]: Only the most recent submaps are visualized with sight for performance reasons.