Skip to content

Commit 6e479f9

Browse files
committed
Implementacion de vision por computador para deteccion simple de pelotas
1 parent 48a2638 commit 6e479f9

File tree

10 files changed

+173
-0
lines changed

10 files changed

+173
-0
lines changed

auv_max_vision_opencv/auv_max_vision_opencv/__init__.py

Whitespace-only changes.

auv_max_vision_opencv/auv_max_vision_opencv/scripts/__init__.py

Whitespace-only changes.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
import rclpy
2+
from rclpy.node import Node
3+
from sensor_msgs.msg import Image
4+
from cv_bridge import CvBridge
5+
import cv2
6+
import numpy as np
7+
8+
class BallDetector(Node):
9+
def __init__(self):
10+
super().__init__('ball_detector')
11+
self.subscription = self.create_subscription(
12+
Image,
13+
'/model/auv_max/camera',
14+
self.image_callback,
15+
10)
16+
self.bridge = CvBridge()
17+
self.publisher = self.create_publisher(Image, '/detected_balls', 10)
18+
19+
def image_callback(self, msg):
20+
# Convertir mensaje ROS Image a imagen para OpenCV
21+
frame = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
22+
23+
# Convertir a escala de grises
24+
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
25+
gray = cv2.GaussianBlur(gray, (15, 15), 0)
26+
27+
# Usar HoughCircles para detectar circulos
28+
circles = cv2.HoughCircles(gray, cv2.HOUGH_GRADIENT, 1, 50, param1=100, param2=30, minRadius=10, maxRadius=100)
29+
30+
if circles is not None:
31+
circles = np.uint16(np.around(circles))
32+
for i in circles[0, :]:
33+
# Dibujar un circulo exterior en la imagen
34+
cv2.circle(frame, (i[0], i[1]), i[2], (0, 255, 0), 2)
35+
# Dibujar un circulo en el centro del circulo exterior
36+
cv2.circle(frame, (i[0], i[1]), 2, (0, 0, 255), 3)
37+
38+
self.get_logger().info('Bolas {} detectadas'.format(len(circles[0, :])))
39+
40+
# Convertir la imagen modificada a un mensaje ROS Image y publicarlo
41+
image_message = self.bridge.cv2_to_imgmsg(frame, encoding='bgr8')
42+
self.publisher.publish(image_message)
43+
44+
def main(args=None):
45+
rclpy.init(args=args)
46+
ball_detector = BallDetector()
47+
rclpy.spin(ball_detector)
48+
ball_detector.destroy_node()
49+
rclpy.shutdown()
50+
51+
if __name__ == '__main__':
52+
main()

auv_max_vision_opencv/package.xml

+18
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>auv_max_vision_opencv</name>
5+
<version>0.0.0</version>
6+
<description>TODO: Package description</description>
7+
<maintainer email="[email protected]">rov-robot</maintainer>
8+
<license>TODO: License declaration</license>
9+
10+
<test_depend>ament_copyright</test_depend>
11+
<test_depend>ament_flake8</test_depend>
12+
<test_depend>ament_pep257</test_depend>
13+
<test_depend>python3-pytest</test_depend>
14+
15+
<export>
16+
<build_type>ament_python</build_type>
17+
</export>
18+
</package>

auv_max_vision_opencv/resource/auv_max_vision_opencv

Whitespace-only changes.

auv_max_vision_opencv/setup.cfg

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
[develop]
2+
script_dir=$base/lib/auv_max_vision_opencv
3+
[install]
4+
install_scripts=$base/lib/auv_max_vision_opencv

auv_max_vision_opencv/setup.py

+26
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
from setuptools import find_packages, setup
2+
3+
package_name = 'auv_max_vision_opencv'
4+
5+
setup(
6+
name=package_name,
7+
version='0.0.0',
8+
packages=find_packages(exclude=['test']),
9+
data_files=[
10+
('share/ament_index/resource_index/packages',
11+
['resource/' + package_name]),
12+
('share/' + package_name, ['package.xml']),
13+
],
14+
install_requires=['setuptools'],
15+
zip_safe=True,
16+
maintainer='rov-robot',
17+
maintainer_email='[email protected]',
18+
description='TODO: Package description',
19+
license='TODO: License declaration',
20+
tests_require=['pytest'],
21+
entry_points={
22+
'console_scripts': [
23+
'detect_balls = auv_max_vision_opencv.scripts.ball_detector:main',
24+
],
25+
},
26+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_copyright.main import main
16+
import pytest
17+
18+
19+
# Remove the `skip` decorator once the source file(s) have a copyright header
20+
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
21+
@pytest.mark.copyright
22+
@pytest.mark.linter
23+
def test_copyright():
24+
rc = main(argv=['.', 'test'])
25+
assert rc == 0, 'Found errors'
+25
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2017 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_flake8.main import main_with_errors
16+
import pytest
17+
18+
19+
@pytest.mark.flake8
20+
@pytest.mark.linter
21+
def test_flake8():
22+
rc, errors = main_with_errors(argv=[])
23+
assert rc == 0, \
24+
'Found %d code style errors / warnings:\n' % len(errors) + \
25+
'\n'.join(errors)
+23
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_pep257.main import main
16+
import pytest
17+
18+
19+
@pytest.mark.linter
20+
@pytest.mark.pep257
21+
def test_pep257():
22+
rc = main(argv=['.', 'test'])
23+
assert rc == 0, 'Found code style errors / warnings'

0 commit comments

Comments
 (0)