Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
L
larm-astro
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Commits
Open sidebar
Inès EL HADRI
larm-astro
Commits
1923389c
Commit
1923389c
authored
Dec 19, 2023
by
Inès EL HADRI
💤
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
1st attempt scan to point cloud
parent
d571a82e
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
52 additions
and
0 deletions
+52
-0
tuto_scan_echo.py
tuto_scan_echo.py
+52
-0
No files found.
tuto_scan_echo.py
0 → 100755
View file @
1923389c
#!python3
import
rclpy
import
math
from
rclpy.node
import
Node
from
sensor_msgs.msg
import
LaserScan
,
PointCloud2
import
sensor_msgs_py.point_cloud2
from
std_msgs.msg
import
Header
rosNode
=
None
def
scan_callback
(
scanMsg
):
global
rosNode
obstacles
=
ranges_to_positions
(
scanMsg
)
sample
=
[
[
round
(
p
[
0
],
2
),
round
(
p
[
1
],
2
),
round
(
p
[
2
],
2
)
]
for
p
in
obstacles
[
10
:
20
]
]
# Publish a msg
pointCloud
=
sensor_msgs_py
.
point_cloud2
.
create_cloud_xyz32
(
Header
(
frame_id
=
'frame'
),
obstacles
)
rosNode
.
get_logger
()
.
info
(
f
"
\n
header:
\n
{scanMsg.header}
\n
number of ranges: {len(scanMsg.ranges)}
\n
Sample: {pointCloud}
\n
"
)
point_publisher
.
publish
(
pointCloud
)
def
ranges_to_positions
(
scan_message
:
LaserScan
)
->
list
:
obstacles
=
[]
angle
=
scan_message
.
angle_min
for
aDistance
in
scan_message
.
ranges
:
if
0.1
<
aDistance
and
aDistance
<
5.0
:
aPoint
=
[
math
.
cos
(
angle
)
*
aDistance
,
math
.
sin
(
angle
)
*
aDistance
,
0
]
obstacles
.
append
(
aPoint
)
angle
+=
scan_message
.
angle_increment
return
obstacles
rclpy
.
init
()
rosNode
=
Node
(
'scan_interpreter'
)
# Initialize a subscriber:
rosNode
.
create_subscription
(
LaserScan
,
'scan'
,
scan_callback
,
10
)
# Initialize a publisher:
point_publisher
=
rosNode
.
create_publisher
(
PointCloud2
,
'/scan_points'
,
10
)
while
True
:
rclpy
.
spin_once
(
rosNode
)
scanInterpret
.
destroy_node
()
rclpy
.
shutdown
()
\ No newline at end of file
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment