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
3fc9324a
Commit
3fc9324a
authored
Jan 08, 2024
by
Inès EL HADRI
💤
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fix cam_driver
parent
dea4fd68
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
15 additions
and
8 deletions
+15
-8
CMakeLists.txt
cam_driver/CMakeLists.txt
+1
-1
cam_driver
cam_driver/scripts/cam_driver
+14
-7
No files found.
cam_driver/CMakeLists.txt
View file @
3fc9324a
cmake_minimum_required
(
VERSION 3.8
)
project
(
tuto_kickoff
)
project
(
cam_driver
)
if
(
CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES
"Clang"
)
add_compile_options
(
-Wall -Wextra -Wpedantic
)
...
...
cam_driver/scripts/cam_driver
View file @
3fc9324a
...
...
@@ -5,6 +5,7 @@ from sensor_msgs.msg import Image
import
pyrealsense2
as
rs
import
signal
,
time
,
numpy
as
np
import
sys
,
cv2
from
cv_bridge
import
CvBridge
class
CameraDriver
(
Node
):
...
...
@@ -17,7 +18,7 @@ class CameraDriver(Node):
self
.
_depth_publisher
=
self
.
create_publisher
(
Image
,
'depth_cam'
,
10
)
# Initialize a clock for the publisher
self
.
create_timer
(
timerFreq
,
self
.
publish_
velo
)
self
.
create_timer
(
timerFreq
,
self
.
publish_
imgs
)
# ------------------------------ Initialize camera ------------------------------ #
...
...
@@ -65,9 +66,16 @@ class CameraDriver(Node):
# Apply colormap on depth image (image must be converted to 8-bit per pixel first)
depth_colormap
=
cv2
.
applyColorMap
(
cv2
.
convertScaleAbs
(
depth_image
,
alpha
=
0.03
),
cv2
.
COLORMAP_JET
)
self
.
_rgb_image
=
color_image
self
.
_depth_image
=
depth_colormap
return
color_image
,
depth_colormap
bridge
=
CvBridge
()
self
.
_rgb_image
=
bridge
.
cv2_to_imgmsg
(
color_image
,
"bgr8"
)
self
.
_depth_image
=
bridge
.
cv2_to_imgmsg
(
depth_colormap
,
"bgr8"
)
self
.
_rgb_image
.
header
.
stamp
=
self
.
get_clock
()
.
now
()
.
to_msg
()
self
.
_depth_image
.
header
.
stamp
=
self
.
_rgb_image
.
header
.
stamp
self
.
_rgb_image
.
header
.
frame_id
=
"image"
self
.
_depth_image
.
header
.
frame_id
=
"depth"
return
self
.
_rgb_image
,
self
.
_depth_image
def
publish_imgs
(
self
):
self
.
publish_rgb
()
...
...
@@ -88,7 +96,7 @@ class CameraDriver(Node):
Publish depth colormap image
"""
self
.
_
rgb
_publisher
.
publish
(
self
.
_depth_image
)
self
.
_
depth
_publisher
.
publish
(
self
.
_depth_image
)
return
0
...
...
@@ -107,11 +115,10 @@ def main():
signal
.
signal
(
signal
.
SIGINT
,
signalInterruption
)
rclpy
.
init
()
rosNode
=
CameraDriver
()
rosNode
=
CameraDriver
(
timerFreq
=
1.0
/
120
)
isOk
=
True
while
isOk
:
rosNode
.
read_imgs
()
rosNode
.
publish_imgs
()
rclpy
.
spin_once
(
rosNode
,
timeout_sec
=
0.001
)
...
...
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