This commit is contained in:
Ronaldson Bellande 2024-06-29 00:58:16 -04:00
parent 42adf8ee35
commit 665adf0eb7
11 changed files with 509 additions and 35 deletions

3
github_scripts/.gitignore vendored Normal file
View File

@ -0,0 +1,3 @@
push.sh
fix_errors.sh
repository_recal.sh

View File

@ -44,6 +44,7 @@ if($ENV{ROS_VERSION} EQUAL 1)
catkin_install_python(
PROGRAMS
src/bellande_2d_computer_vision_prediction.py
src/bellande_2d_computer_vision_face_detection.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
endif()
@ -51,10 +52,12 @@ endif()
# Install Python scripts, configuration files, and launch files
if($ENV{ROS_VERSION} EQUAL "1")
install(PROGRAMS src/bellande_2d_computer_vision_prediction.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
install(PROGRAMS src/bellande_2d_computer_vision_face_detection.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
install(DIRECTORY config/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config)
install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch)
else()
install(PROGRAMS src/bellande_2d_computer_vision_prediction.py DESTINATION lib/${PROJECT_NAME})
install(PROGRAMS src/bellande_2d_computer_vision_face_detection.py DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}/config)
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch)
ament_package()

View File

@ -0,0 +1,86 @@
import os
import sys
import subprocess
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
def ros1_launch_description():
# Get command-line arguments
args = sys.argv[1:]
# Construct the ROS 1 launch commandi
roslaunch_command = ["roslaunch", "ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_face_detection.launch"] + args
roslaunch_command.extend([
"usb_cam", "usb_cam_node", "name:=camera",
"video_device:=/dev/video0",
"image_width:=640",
"image_height:=480",
"pixel_format:=yuyv",
"camera_frame_id:=usb_cam",
"io_method:=mmap"
])
roslaunch_command.extend([
"ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_face_detection.py", "name:=face_detection_node"
])
roslaunch_command.extend([
"rviz", "rviz", "name:=rviz",
"args:=-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz"
])
# Execute the launch command
subprocess.call(roslaunch_command)
def ros2_launch_description():
nodes_to_launch = []
nodes_to_launch.append(Node(
package='usb_cam',
executable='usb_cam_node',
name='camera',
output='screen',
parameters=[{
'video_device': '/dev/video0',
'image_width': 640,
'image_height': 480,
'pixel_format': 'yuyv',
'camera_frame_id': 'usb_cam',
'io_method': 'mmap'
}]
))
nodes_to_launch.append(Node(
package='ros_web_api_bellande_2d_computer_vision',
executable='bellande_2d_computer_vision_face_detection.py',
name='prediction_node',
output='screen',
remappings=[('camera/image_raw', '/usb_cam/image_raw')]
))
nodes_to_launch.append(Node(
package='rviz2',
executable='rviz2',
name='rviz',
arguments=['-d', '$(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz']
))
return LaunchDescription(nodes_to_launch)
if __name__ == "__main__":
ros_version = os.getenv("ROS_VERSION")
if ros_version == "1":
ros1_launch_description()
elif ros_version == "2":
ros2_launch_description()
else:
print("Unsupported ROS version. Please set the ROS_VERSION environment variable to '1' for ROS 1 or '2' for ROS 2.")
sys.exit(1)

View File

@ -12,14 +12,68 @@ def ros1_launch_description():
args = sys.argv[1:]
# Construct the ROS 1 launch commandi
roslaunch_command = ["roslaunch", "bellande_2d_computer_vision_prediction", "bellande_step_api_2d.launch"] + args
roslaunch_command = ["roslaunch", "ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_prediction.launch"] + args
roslaunch_command.extend([
"usb_cam", "usb_cam_node", "name:=camera",
"video_device:=/dev/video0",
"image_width:=640",
"image_height:=480",
"pixel_format:=yuyv",
"camera_frame_id:=usb_cam",
"io_method:=mmap"
])
roslaunch_command.extend([
"ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_prediction.py", "name:=prediction_node"
])
roslaunch_command.extend([
"rviz", "rviz", "name:=rviz",
"args:=-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz"
])
# Execute the launch command
subprocess.call(roslaunch_command)
def ros2_launch_description():
pass
nodes_to_launch = []
nodes_to_launch.append(Node(
package='usb_cam',
executable='usb_cam_node',
name='camera',
output='screen',
parameters=[{
'video_device': '/dev/video0',
'image_width': 640,
'image_height': 480,
'pixel_format': 'yuyv',
'camera_frame_id': 'usb_cam',
'io_method': 'mmap'
}]
))
nodes_to_launch.append(Node(
package='ros_web_api_bellande_2d_computer_vision',
executable='bellande_2d_computer_vision_prediction.py',
name='prediction_node',
output='screen',
remappings=[('camera/image_raw', '/usb_cam/image_raw')]
))
nodes_to_launch.append(Node(
package='rviz2',
executable='rviz2',
name='rviz',
arguments=['-d', '$(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz']
))
return LaunchDescription(nodes_to_launch)
if __name__ == "__main__":
ros_version = os.getenv("ROS_VERSION")

View File

@ -0,0 +1,36 @@
<?xml version="1.0"?>
<!--
Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande
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.
-->
<launch>
<node name="camera" pkg="usb_cam" type="usb_cam_node" output="screen">
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap" />
</node>
<node name="face_detection_node" pkg="ros_web_api_bellande_2d_computer_vision"
type="bellande_2d_computer_vision_face_detection.py"
output="screen">
<remap from="camera/image_raw" to="/usb_cam/image_raw" />
</node>
<node name="rviz" pkg="rviz" type="rviz"
args="-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz" />
</launch>

View File

@ -15,8 +15,21 @@ License for the specific language governing permissions and limitations under
the License.
-->
<launch>
<node pkg="bellande_2d_computer_vision_prediction"
type="bellande_2d_computer_vision_prediction.py"
name="bellande_2d_computer_vision_prediction_node" output="screen">
<node name="camera" pkg="usb_cam" type="usb_cam_node" output="screen">
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap" />
</node>
<node name="prediction_node" pkg="ros_web_api_bellande_2d_computer_vision"
type="bellande_2d_computer_vision_prediction.py" output="screen">
<remap from="camera/image_raw" to="/usb_cam/image_raw" />
</node>
<node name="rviz" pkg="rviz" type="rviz"
args="-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz" />
</launch>

View File

@ -0,0 +1,143 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Image1
- /Image2
Splitter Ratio: 0.5
Tree Height: 549
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Image
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /usb_cam/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Raw Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /processed_image
Max Value: 1
Median window: 5
Min Value: 0
Name: Processed Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Topic: /initialpose
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 10
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.0500000007
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 0.785398006
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002c4000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000022b000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 65
Y: 60
Raw Image:
collapsed: false
Processed Image:
collapsed: false

View File

@ -1,22 +0,0 @@
#!/bin/bash
# Create and navigate to build directory
mkdir -p build && cd build
# Build package
if [ $ROS_VERSION -eq 1 ]; then
cmake -DROS_VERSION=1 ..
make -j$(nproc)
else
cmake -DROS_VERSION=2 ..
make -j$(nproc)
fi
# Source package setup file
source devel/setup.bash
# Run rosdep
rosdep install --from-paths ../src --ignore-src -y
# Return to package root directory
cd ..

View File

@ -3,7 +3,7 @@ from catkin_pkg.python_setup import generate_distutils_setup
# fetch values from package.xml
setup_args = generate_distutils_setup(
scripts=['src/bellande_2d_computer_vision_prediction.py'],
scripts=['src/bellande_2d_computer_vision_prediction.py', 'src/bellande_2d_computer_vision_face_detection.py'],
packages=['ros_web_api_bellande_2d_computer_vision'],
package_dir={'': 'src'},
)

View File

@ -0,0 +1,94 @@
import json
import os
import requests
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
def face_detection(image):
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(image, desired_encoding="bgr8")
_, img_encoded = cv2.imencode('.jpg', cv_image)
img_base64 = base64.b64encode(img_encoded).decode('utf-8')
payload = {
"image": img_base64
}
response = requests.post(api_url, json=payload)
if response.status_code == 200:
result = response.json()
for face in result['faces']:
x, y, w, h = face['bbox']
cv2.rectangle(cv_image, (x, y), (x+w, y+h), (0, 255, 0), 2)
processed_msg = bridge.cv2_to_imgmsg(cv_image, encoding="bgr8")
return processed_msg
else:
print(f"Error: {response.status_code} - {response.text}")
return None
def image_callback(msg):
processed_img = face_detection(msg)
if processed_img:
pub.publish(processed_img)
def main():
global api_url, pub
# Get the absolute path to the config file
config_file_path = os.path.join(os.path.dirname(__file__), '../config/configs.json')
# Check if the config file exists
if not os.path.exists(config_file_path):
print("Config file not found:", config_file_path)
return
# Read configuration from config.json
with open(config_file_path, 'r') as config_file:
config = json.load(config_file)
url = config['url']
endpoint_path = config['endpoint_path']["face_detection"]
# Initialize ROS node
if ros_version == "1":
rospy.init_node('face_detection_node', anonymous=True)
pub = rospy.Publisher('processed_image', Image, queue_size=10)
sub = rospy.Subscriber('camera/image_raw', Image, image_callback)
elif ros_version == "2":
rclpy.init()
node = rclpy.create_node('face_detection_node')
pub = node.create_publisher(Image, 'processed_image', 10)
sub = node.create_subscription(Image, 'camera/image_raw', image_callback, 10)
api_url = f"{url}{endpoint_path}"
try:
print("Face detection node is running. Ctrl+C to exit.")
if ros_version == "1":
rospy.spin()
elif ros_version == "2":
rclpy.spin(node)
except KeyboardInterrupt:
print("Shutting down face detection node.")
except Exception as e:
print(f"An error occurred: {str(e)}")
finally:
if ros_version == "2":
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
ros_version = os.getenv("ROS_VERSION")
if ros_version == "1":
import rospy
elif ros_version == "2":
import rclpy
main()

View File

@ -1,22 +1,87 @@
import json
import os
import requests
import cv2
import base64
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from std_msgs.msg import String
def predict(image):
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(image, desired_encoding="bgr8")
_, img_encoded = cv2.imencode('.jpg', cv_image)
img_base64 = base64.b64encode(img_encoded).decode('utf-8')
payload = {
"image": img_base64
}
response = requests.post(api_url, json=payload)
if response.status_code == 200:
result = response.json()
prediction = result['prediction']
confidence = result['confidence']
prediction_msg = f"Prediction: {prediction}, Confidence: {confidence:.2f}"
return String(prediction_msg)
else:
print(f"Error: {response.status_code} - {response.text}")
return None
def image_callback(msg):
prediction = predict(msg)
if prediction:
pub.publish(prediction)
def main():
# Get the absolute path to the config file
config_file_path = os.path.join(os.path.dirname(__file__), '../config/configs.json')
global api_url, pub
# Check if the config file exists
config_file_path = os.path.join(os.path.dirname(__file__), '../config/configs.json')
if not os.path.exists(config_file_path):
print("Config file not found:", config_file_path)
return
# Read configuration from config.json
with open(config_file_path, 'r') as config_file:
config = json.load(config_file)
url = config['url']
endpoint_path = config['endpoint_path']["2d"]
endpoint_path = config['endpoint_path']["prediction"]
# Initialize ROS node
if ros_version == "1":
rospy.init_node('prediction_node', anonymous=True)
pub = rospy.Publisher('prediction_result', String, queue_size=10)
sub = rospy.Subscriber('camera/image_raw', Image, image_callback)
elif ros_version == "2":
rclpy.init()
node = rclpy.create_node('prediction_node')
pub = node.create_publisher(String, 'prediction_result', 10)
sub = node.create_subscription(Image, 'camera/image_raw', image_callback, 10)
api_url = f"{url}{endpoint_path}"
try:
print("Prediction node is running. Ctrl+C to exit.")
if ros_version == "1":
rospy.spin()
elif ros_version == "2":
rclpy.spin(node)
except KeyboardInterrupt:
print("Shutting down prediction node.")
except Exception as e:
print(f"An error occurred: {str(e)}")
finally:
if ros_version == "2":
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
ros_version = os.getenv("ROS_VERSION")
@ -24,5 +89,4 @@ if __name__ == '__main__':
import rospy
elif ros_version == "2":
import rclpy
main()