Skip to content

Commit ec7cc58

Browse files
Merge pull request #189 from CooperUnion/user/isaiahrivera21/object_detection_pr
User/isaiahrivera21/object detection pr
2 parents aaf3e18 + 87ea95e commit ec7cc58

File tree

28 files changed

+853
-0
lines changed

28 files changed

+853
-0
lines changed
Lines changed: 18 additions & 0 deletions
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>place_object_globally_package</name>
5+
<version>0.0.0</version>
6+
<description>TODO: Package description</description>
7+
<maintainer email="vaibhav.hariani@gmail.com">eeadmin</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>

ros2/PlaceObjectsGlobally/place_object_globally_ws/src/place_object_globally_package/place_object_globally_package/__init__.py

Whitespace-only changes.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
1+
import rclpy
2+
from rclpy.node import Node
3+
from nav_msgs.msg import Odometry
4+
from geometry_msgs.msg import Pose, PoseWithCovariance
5+
6+
7+
class ObjGlobalLocation(Node):
8+
def __init__(self):
9+
super().__init__('Object_Global_Location_Node')
10+
11+
# Might need to apply on offset because the object location is given wrt the zed's left camera
12+
13+
# in this contect we only care about the vehicle's x and y pos
14+
self.vehicle_x = None
15+
self.vehicle_y = None
16+
17+
self.obj_x = None
18+
self.obj_y = None
19+
20+
# Subscribe to get information on the vehicle and object positions
21+
self.obj_information_subscription = self.create_subscription(
22+
Yolo,
23+
'dist_at_obj',
24+
self.obj_information_callback,
25+
10)
26+
27+
self.obj_information_subscription
28+
29+
self.vehicle_position_subscription = self.create_subscription(
30+
Odometry,
31+
'encoder_odom',
32+
self.vehicle_position_callback,
33+
10)
34+
35+
self.vehicle_position_subscription
36+
37+
# Publish the object's location wrt to where we started
38+
self.object_global_location_publisher = self.create_publisher(Pose, '/pose', 10) # want to change to pose with covar in the future
39+
40+
timer_period = 0.1 # seconds
41+
self.timer = self.create_timer(timer_period, self.timer_callback)
42+
43+
def obj_information_callback(self,msg):
44+
self.obj_x = msg.x
45+
self.obj_y = msg.y
46+
47+
def vehicle_position_callback(self,msg):
48+
self.vehicle_x = msg.pose.pose.position.x
49+
self.vehicle_y = msg.pose.pose.position.y
50+
51+
def timer_callback(self):
52+
obj_location = PoseWithCovariance()
53+
54+
# Covariance Matrix
55+
obj_location.covariance = [1.0, 0.0, 0.0, 0.0, 0.0, 0.0,
56+
0.0, 1.0, 0.0, 0.0, 0.0, 0.0,
57+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
58+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
59+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
60+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,]
61+
62+
obj_location.pose.position.x = self.vehicle_x + self.obj_x
63+
obj_location.pose.position.y = self.vehicle_y + self.obj_y
64+
obj_location.pose.position.z = 0.0
65+
66+
obj_location.pose.orientation.x = 0.0
67+
obj_location.pose.orientation.y = 0.0
68+
obj_location.pose.orientation.z = 0.0
69+
obj_location.pose.orientation.w = 0.0
70+
71+
self.object_global_location_publisher.publish(obj_location)

ros2/PlaceObjectsGlobally/place_object_globally_ws/src/place_object_globally_package/resource/place_object_globally_package

Whitespace-only changes.
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
[develop]
2+
script_dir=$base/lib/place_object_globally_package
3+
[install]
4+
install_scripts=$base/lib/place_object_globally_package
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
from setuptools import find_packages, setup
2+
3+
package_name = 'place_object_globally_package'
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='eeadmin',
17+
maintainer_email='vaibhav.hariani@gmail.com',
18+
description='TODO: Package description',
19+
license='TODO: License declaration',
20+
tests_require=['pytest'],
21+
entry_points={
22+
'console_scripts': [
23+
'place_object_globally_node = place_object_globally_package.place_object_globally_node: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'
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)
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'

ros2/Yolo-Object-Detection/README.md

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
## How to Run Object Detection Stack
2+
3+
The object detection stack is a ros2 package. It can be built and ran like any other standard ros2 package.
4+
5+
Run the following:
6+
7+
```
8+
colcon build
9+
```
10+
11+
```
12+
source install/setup.bash
13+
```
14+
15+
```
16+
ros2 run dist_to_obj_package dist_to_obj_node
17+
```
18+
19+
## Errors that might occur on launch
20+
21+
If the ZED camera is not plugged in the following error will pop up:
22+
23+
```
24+
Camera Open : CAMERA NOT DETECTED. Exit program.
25+
```
26+
27+
Sometimes this error will pop up when trying to start object detection:
28+
29+
```
30+
NO GPU DETECTED
31+
```
32+
33+
While it doesn't happen often in the even that it does starting the computer fixes it.
Binary file not shown.

ros2/Yolo-Object-Detection/dist_to_obj_ws/src/dist_to_obj_package/dist_to_obj_package/__init__.py

Whitespace-only changes.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
1+
from geometry_msgs.msg import Twist
2+
from std_msgs.msg import Float64
3+
from sensor_msgs.msg import Image
4+
5+
import rclpy
6+
from rclpy.node import Node
7+
from rclpy.qos import qos_profile_sensor_data
8+
from .object_detection_submodule.object_detection import ObjectDetection
9+
import cv2
10+
import sys
11+
from cv_bridge import CvBridge
12+
from yolo_interfaces.msg import Yolo
13+
14+
class Dist_To_Object(Node):
15+
def __init__(self,model):
16+
super().__init__('dist_to_obj_node')
17+
self._bridge = CvBridge()
18+
timer_period = 0.01 # seconds
19+
self.timer = self.create_timer(timer_period, self.timer_callback)
20+
self.img_publisher = self.create_publisher(Image, "/obj_detection_img", 10)
21+
self.distToObj_publisher = self.create_publisher(Yolo, '/dist_to_obj',10)
22+
self.model = model
23+
self.model.init_model()
24+
25+
def timer_callback(self):
26+
msg = Yolo()
27+
28+
# Get keyboard input
29+
key = cv2.waitKeyEx(1)
30+
31+
# Exit loop if 'q' key is pressed
32+
if key == ord('q') or key == 27: # 'q' or Esc keyr
33+
self.model.close_cam() # Close camera before exiting
34+
self.get_logger().info('Exiting node...')
35+
sys.exit()
36+
# rclpy.shutdown() # Shutdown ROS2
37+
# return
38+
39+
# Run object detection
40+
self.model.objectDetection()
41+
image = self.model.annotated_frame
42+
image = self._bridge.cv2_to_imgmsg(image, encoding="passthrough")
43+
self.img_publisher.publish(image)
44+
45+
46+
msg.dist = self.model.distance
47+
msg.name = self.model.obj_name
48+
msg.x = self.model.center_x
49+
msg.y = self.model.center_y
50+
self.distToObj_publisher.publish(msg)
51+
52+
self.get_logger().info("\n ----------------------------------------------\n")
53+
self.get_logger().info('X Coord: %f \n' % msg.x)
54+
self.get_logger().info('Y Coord: %f \n' % msg.y)
55+
self.get_logger().info('Distance to object: %f \n' % msg.dist)
56+
self.get_logger().info('Name to object: %s \n' % msg.name)
57+
self.get_logger().info("\n ----------------------------------------------\n")
58+
59+
60+
61+
def main(args=None):
62+
# rclpy.init(args=args) # Initialize ROS2 program
63+
# model = ObjectDetection(display=True)
64+
# node = Dist_To_Object(model=model) # Instantiate Node
65+
# rclpy.spin(node) # Puts the node in an infinite loop
66+
# # Clean shutdown should be at the end of every node
67+
# node.destroy_node()
68+
# rclpy.shutdown()
69+
70+
rclpy.init(args=args) # Initialize ROS2 program
71+
model = ObjectDetection(display=True)
72+
node = Dist_To_Object(model=model) # Instantiate Node
73+
rclpy.spin(node)
74+
node.destroy_node()
75+
rclpy.shutdown()
76+
77+
if __name__ == '__main__':
78+
main()

ros2/Yolo-Object-Detection/dist_to_obj_ws/src/dist_to_obj_package/dist_to_obj_package/object_detection_submodule/__init__.py

Whitespace-only changes.

0 commit comments

Comments
 (0)