Skip to content

User/isaiahrivera21/object detection pr #189

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>place_object_globally_package</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="vaibhav.hariani@gmail.com">eeadmin</maintainer>
<license>TODO: License declaration</license>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
import rclpy
from rclpy.node import Node
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Pose, PoseWithCovariance


class ObjGlobalLocation(Node):
def __init__(self):
super().__init__('Object_Global_Location_Node')

# Might need to apply on offset because the object location is given wrt the zed's left camera

# in this contect we only care about the vehicle's x and y pos
self.vehicle_x = None
self.vehicle_y = None

self.obj_x = None
self.obj_y = None

# Subscribe to get information on the vehicle and object positions
self.obj_information_subscription = self.create_subscription(
Yolo,
'dist_at_obj',
self.obj_information_callback,
10)

self.obj_information_subscription

self.vehicle_position_subscription = self.create_subscription(
Odometry,
'encoder_odom',
self.vehicle_position_callback,
10)

self.vehicle_position_subscription

# Publish the object's location wrt to where we started
self.object_global_location_publisher = self.create_publisher(Pose, '/pose', 10) # want to change to pose with covar in the future

timer_period = 0.1 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)

def obj_information_callback(self,msg):
self.obj_x = msg.x
self.obj_y = msg.y

def vehicle_position_callback(self,msg):
self.vehicle_x = msg.pose.pose.position.x
self.vehicle_y = msg.pose.pose.position.y

def timer_callback(self):
obj_location = PoseWithCovariance()

# Covariance Matrix
obj_location.covariance = [1.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 1.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,]

obj_location.pose.position.x = self.vehicle_x + self.obj_x
obj_location.pose.position.y = self.vehicle_y + self.obj_y
obj_location.pose.position.z = 0.0

obj_location.pose.orientation.x = 0.0
obj_location.pose.orientation.y = 0.0
obj_location.pose.orientation.z = 0.0
obj_location.pose.orientation.w = 0.0

self.object_global_location_publisher.publish(obj_location)
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/place_object_globally_package
[install]
install_scripts=$base/lib/place_object_globally_package
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
from setuptools import find_packages, setup

package_name = 'place_object_globally_package'

setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='eeadmin',
maintainer_email='vaibhav.hariani@gmail.com',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'place_object_globally_node = place_object_globally_package.place_object_globally_node:main'
],
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'
33 changes: 33 additions & 0 deletions ros2/Yolo-Object-Detection/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
## How to Run Object Detection Stack

The object detection stack is a ros2 package. It can be built and ran like any other standard ros2 package.

Run the following:

```
colcon build
```

```
source install/setup.bash
```

```
ros2 run dist_to_obj_package dist_to_obj_node
```

## Errors that might occur on launch

If the ZED camera is not plugged in the following error will pop up:

```
Camera Open : CAMERA NOT DETECTED. Exit program.
```

Sometimes this error will pop up when trying to start object detection:

```
NO GPU DETECTED
```

While it doesn't happen often in the even that it does starting the computer fixes it.
Binary file added ros2/Yolo-Object-Detection/dist_to_obj_ws/best.pt
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
from geometry_msgs.msg import Twist
from std_msgs.msg import Float64
from sensor_msgs.msg import Image

import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from .object_detection_submodule.object_detection import ObjectDetection
import cv2
import sys
from cv_bridge import CvBridge
from yolo_interfaces.msg import Yolo

class Dist_To_Object(Node):
def __init__(self,model):
super().__init__('dist_to_obj_node')
self._bridge = CvBridge()
timer_period = 0.01 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.img_publisher = self.create_publisher(Image, "/obj_detection_img", 10)
self.distToObj_publisher = self.create_publisher(Yolo, '/dist_to_obj',10)
self.model = model
self.model.init_model()

def timer_callback(self):
msg = Yolo()

# Get keyboard input
key = cv2.waitKeyEx(1)

# Exit loop if 'q' key is pressed
if key == ord('q') or key == 27: # 'q' or Esc keyr
self.model.close_cam() # Close camera before exiting
self.get_logger().info('Exiting node...')
sys.exit()
# rclpy.shutdown() # Shutdown ROS2
# return

# Run object detection
self.model.objectDetection()
image = self.model.annotated_frame
image = self._bridge.cv2_to_imgmsg(image, encoding="passthrough")
self.img_publisher.publish(image)


msg.dist = self.model.distance
msg.name = self.model.obj_name
msg.x = self.model.center_x
msg.y = self.model.center_y
self.distToObj_publisher.publish(msg)

self.get_logger().info("\n ----------------------------------------------\n")
self.get_logger().info('X Coord: %f \n' % msg.x)
self.get_logger().info('Y Coord: %f \n' % msg.y)
self.get_logger().info('Distance to object: %f \n' % msg.dist)
self.get_logger().info('Name to object: %s \n' % msg.name)
self.get_logger().info("\n ----------------------------------------------\n")



def main(args=None):
# rclpy.init(args=args) # Initialize ROS2 program
# model = ObjectDetection(display=True)
# node = Dist_To_Object(model=model) # Instantiate Node
# rclpy.spin(node) # Puts the node in an infinite loop
# # Clean shutdown should be at the end of every node
# node.destroy_node()
# rclpy.shutdown()

rclpy.init(args=args) # Initialize ROS2 program
model = ObjectDetection(display=True)
node = Dist_To_Object(model=model) # Instantiate Node
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()
Loading
Loading