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
adacae68
Commit
adacae68
authored
Jan 22, 2024
by
Inès EL HADRI
💤
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Change HSV tuner to use the function of the CameraVision class
parent
653e6fda
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
62 additions
and
90 deletions
+62
-90
CMakeLists.txt
grp_astro/CMakeLists.txt
+1
-1
tbot_launch.yaml
grp_astro/launch/tbot_launch.yaml
+1
-1
cam_driver.py
grp_astro/src/cam_driver.py
+5
-4
cam_vision.py
grp_astro/src/cam_vision.py
+40
-31
mask_tuner.py
grp_astro/src/config/mask_tuner.py
+15
-53
No files found.
grp_astro/CMakeLists.txt
View file @
adacae68
...
@@ -51,7 +51,7 @@ install(DIRECTORY
...
@@ -51,7 +51,7 @@ install(DIRECTORY
# Python scripts
# Python scripts
install
(
PROGRAMS
install
(
PROGRAMS
src/cam_driver.py
src/cam_driver.py
src/cam_vision
src/cam_vision
.py
src/reactive_move
src/reactive_move
src/scan2point_cloud
src/scan2point_cloud
src/bottle_mapping
src/bottle_mapping
...
...
grp_astro/launch/tbot_launch.yaml
View file @
adacae68
...
@@ -23,7 +23,7 @@ launch:
...
@@ -23,7 +23,7 @@ launch:
# Publish if there is a bottle in the field of view
# Publish if there is a bottle in the field of view
-
node
:
-
node
:
pkg
:
"
grp_astro"
pkg
:
"
grp_astro"
exec
:
"
cam_vision"
exec
:
"
cam_vision
.py
"
name
:
"
cam_vision"
name
:
"
cam_vision"
# Launch a SLAM algorithm
# Launch a SLAM algorithm
...
...
grp_astro/src/cam_driver.py
View file @
adacae68
...
@@ -11,7 +11,8 @@ from cv_bridge import CvBridge
...
@@ -11,7 +11,8 @@ from cv_bridge import CvBridge
class
CameraDriver
(
Node
):
class
CameraDriver
(
Node
):
def
__init__
(
self
,
name
=
"cam_driver"
,
timerFreq
=
1
/
60.0
):
def
__init__
(
self
,
name
=
"cam_driver"
,
timerFreq
=
1
/
60.0
,
isRos
=
True
):
if
isRos
:
super
()
.
__init__
(
name
)
# Create the node
super
()
.
__init__
(
name
)
# Create the node
# Initialize publishers:
# Initialize publishers:
...
...
grp_astro/src/cam_vision
→
grp_astro/src/cam_vision
.py
View file @
adacae68
...
@@ -15,9 +15,11 @@ import pyrealsense2 as rs
...
@@ -15,9 +15,11 @@ import pyrealsense2 as rs
class
CameraVision
(
CameraDriver
):
class
CameraVision
(
CameraDriver
):
def
__init__
(
self
,
name
=
"cam_vision"
,
timerFreq
=
1
/
60.0
):
def
__init__
(
self
,
name
=
"cam_vision"
,
timerFreq
=
1
/
60.0
,
isRos
=
True
):
super
()
.
__init__
(
name
,
timerFreq
)
# Create the node
super
()
.
__init__
(
name
,
timerFreq
,
isRos
)
# Create the node
if
isRos
:
# Load parameters
# Load parameters
directory
=
pathlib
.
PurePath
(
__file__
)
.
parent
directory
=
pathlib
.
PurePath
(
__file__
)
.
parent
try
:
try
:
...
@@ -40,6 +42,7 @@ class CameraVision(CameraDriver):
...
@@ -40,6 +42,7 @@ class CameraVision(CameraDriver):
print
(
"Set HSV params to default values :
\n
- low : {self._low}
\n
- high {self._high}"
)
print
(
"Set HSV params to default values :
\n
- low : {self._low}
\n
- high {self._high}"
)
# Node parameters
# Node parameters
self
.
declare_parameters
(
self
.
declare_parameters
(
namespace
=
''
,
namespace
=
''
,
...
@@ -109,6 +112,16 @@ class CameraVision(CameraDriver):
...
@@ -109,6 +112,16 @@ class CameraVision(CameraDriver):
self
.
_bottle_relative_pos_publisher
.
publish
(
relative_position
)
self
.
_bottle_relative_pos_publisher
.
publish
(
relative_position
)
def
maskImage
(
self
,
hsv_img
):
# Seuillage par colorimétrie
mask
=
cv2
.
inRange
(
hsv_img
,
self
.
_low
,
self
.
_high
)
# Réduction du bruit
mask
=
cv2
.
erode
(
mask
,
self
.
_kernel
,
iterations
=
4
)
mask
=
cv2
.
dilate
(
mask
,
self
.
_kernel
,
iterations
=
4
)
return
mask
# Node internal loop
# Node internal loop
def
loop
(
self
):
def
loop
(
self
):
...
@@ -124,12 +137,8 @@ class CameraVision(CameraDriver):
...
@@ -124,12 +137,8 @@ class CameraVision(CameraDriver):
# Convert image to HSV for easier thresholding
# Convert image to HSV for easier thresholding
image
=
cv2
.
cvtColor
(
color_image
,
cv2
.
COLOR_BGR2HSV
)
image
=
cv2
.
cvtColor
(
color_image
,
cv2
.
COLOR_BGR2HSV
)
# Seuillage par colorimétrie
# Create a mask based on HSV threshold, noise reduction
mask
=
cv2
.
inRange
(
image
,
self
.
_low
,
self
.
_high
)
mask
=
self
.
maskImage
(
image
)
# Réduction du bruit
mask
=
cv2
.
erode
(
mask
,
self
.
_kernel
,
iterations
=
4
)
mask
=
cv2
.
dilate
(
mask
,
self
.
_kernel
,
iterations
=
4
)
# Segmentation using shape matching
# Segmentation using shape matching
...
...
grp_astro/src/config/mask_tuner.py
View file @
adacae68
...
@@ -9,62 +9,29 @@ import pyrealsense2 as rs
...
@@ -9,62 +9,29 @@ import pyrealsense2 as rs
import
signal
,
time
,
numpy
as
np
import
signal
,
time
,
numpy
as
np
import
sys
,
cv2
import
sys
,
cv2
import
time
import
time
sys
.
path
.
append
(
".."
)
from
cam_vision
import
CameraVision
# Configure depth and color streams
camera
=
CameraVision
(
isRos
=
False
)
# Init camera
pipeline
=
rs
.
pipeline
()
config
=
rs
.
config
()
# Get device product line for setting a supporting resolution
pipeline_wrapper
=
rs
.
pipeline_wrapper
(
pipeline
)
pipeline_profile
=
config
.
resolve
(
pipeline_wrapper
)
device
=
pipeline_profile
.
get_device
()
device_product_line
=
str
(
device
.
get_info
(
rs
.
camera_info
.
product_line
))
print
(
f
"Connect: {device_product_line}"
)
found_rgb
=
True
for
s
in
device
.
sensors
:
print
(
"Name:"
+
s
.
get_info
(
rs
.
camera_info
.
name
)
)
if
s
.
get_info
(
rs
.
camera_info
.
name
)
==
'RGB Camera'
:
found_rgb
=
True
if
not
(
found_rgb
):
print
(
"Depth camera required !!!"
)
exit
(
0
)
config
.
enable_stream
(
rs
.
stream
.
color
,
width
=
848
,
height
=
480
,
format
=
rs
.
format
.
bgr8
,
framerate
=
60
)
config
.
enable_stream
(
rs
.
stream
.
depth
,
width
=
848
,
height
=
480
,
format
=
rs
.
format
.
z16
,
framerate
=
60
)
# Capture ctrl-c event
isOk
=
True
def
signalInterruption
(
signum
,
frame
):
global
isOk
print
(
"
\n
Ctrl-c pressed"
)
isOk
=
False
signal
.
signal
(
signal
.
SIGINT
,
signalInterruption
)
# Start streaming
pipeline
.
start
(
config
)
# VARIABLES
# VARIABLES
low
=
np
.
array
([
179
,
255
,
255
])
# Set to max so detected values will be inferior
camera
.
_
low
=
np
.
array
([
179
,
255
,
255
])
# Set to max so detected values will be inferior
high
=
np
.
array
([
0
,
0
,
0
])
#Set to min so detected values will be superior
camera
.
_
high
=
np
.
array
([
0
,
0
,
0
])
#Set to min so detected values will be superior
kernel
=
np
.
ones
((
5
,
5
),
np
.
uint8
)
camera
.
_
kernel
=
np
.
ones
((
5
,
5
),
np
.
uint8
)
# Skip the first frames of the camera (for some reason they don't work well)
# Skip the first frames of the camera (for some reason they don't work well)
for
i
in
range
(
20
):
for
i
in
range
(
20
):
frames
=
pipeline
.
wait_for_frames
()
frames
=
camera
.
_
pipeline
.
wait_for_frames
()
color_frame
=
frames
.
get_color_frame
()
color_frame
=
frames
.
get_color_frame
()
if
color_frame
is
not
None
:
if
color_frame
is
None
:
exit
exit
# Convert image to numpy arrays
# Convert image to numpy arrays
color_image
=
np
.
asanyarray
(
color_frame
.
get_data
())
color_image
=
np
.
asanyarray
(
color_frame
.
get_data
())
# Convert image to HSV for easier thresholding
# Convert image to HSV for easier thresholding
hsv_image
=
cv2
.
cvtColor
(
color_image
,
cv2
.
COLOR_BGR2HSV
)
hsv_image
=
cv2
.
cvtColor
(
color_image
,
cv2
.
COLOR_BGR2HSV
)
...
@@ -82,17 +49,12 @@ hMargin = 13
...
@@ -82,17 +49,12 @@ hMargin = 13
sMargin
=
10
sMargin
=
10
vMargin
=
10
vMargin
=
10
low
=
np
.
array
([
min
(
H
)
-
hMargin
,
min
(
S
)
-
sMargin
,
min
(
V
)
-
vMargin
])
camera
.
_
low
=
np
.
array
([
min
(
H
)
-
hMargin
,
min
(
S
)
-
sMargin
,
min
(
V
)
-
vMargin
])
high
=
np
.
array
([
max
(
H
)
+
hMargin
,
max
(
S
)
+
sMargin
,
max
(
V
)
+
vMargin
])
camera
.
_
high
=
np
.
array
([
max
(
H
)
+
hMargin
,
max
(
S
)
+
sMargin
,
max
(
V
)
+
vMargin
])
print
(
"-> Low and high HSV saved in 'hsv_params' file :"
,
low
,
high
)
print
(
"-> Low and high HSV saved in 'hsv_params' file :"
,
camera
.
_low
,
camera
.
_
high
)
# Vision
# Vision
# Seuillage par colorimétrie
mask
=
camera
.
maskImage
(
hsv_image
)
mask
=
cv2
.
inRange
(
hsv_image
,
low
,
high
)
# Réduction du bruit
mask
=
cv2
.
erode
(
mask
,
kernel
,
iterations
=
4
)
mask
=
cv2
.
dilate
(
mask
,
kernel
,
iterations
=
4
)
mask_rgb
=
cv2
.
cvtColor
(
mask
,
cv2
.
COLOR_GRAY2BGR
)
mask_rgb
=
cv2
.
cvtColor
(
mask
,
cv2
.
COLOR_GRAY2BGR
)
...
@@ -106,8 +68,8 @@ cv2.waitKey(0)
...
@@ -106,8 +68,8 @@ cv2.waitKey(0)
# Save values in a file
# Save values in a file
file
=
open
(
"hsv_params"
,
"w"
)
file
=
open
(
"hsv_params"
,
"w"
)
file
.
write
(
str
(
low
)
+
","
+
str
(
high
))
file
.
write
(
str
(
camera
.
_low
)
+
","
+
str
(
camera
.
_
high
))
file
.
close
()
file
.
close
()
# Stop streaming
# Stop streaming
print
(
"
\n
Ending..."
)
print
(
"
\n
Ending..."
)
pipeline
.
stop
()
camera
.
_pipeline
.
stop
()
\ No newline at end of file
\ 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