cv
This commit is contained in:
		| @@ -44,6 +44,9 @@ if($ENV{ROS_VERSION} EQUAL 1) | ||||
|   catkin_install_python( | ||||
|     PROGRAMS | ||||
|     src/bellande_3d_computer_vision_prediction.py | ||||
|     src/bellande_3d_computer_vision_object_detection.py | ||||
|     src/bellande_3d_computer_vision_instance_segmentation.py | ||||
|     src/bellande_3d_computer_vision_semantic_segmentation.py | ||||
|     DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | ||||
|   ) | ||||
| endif() | ||||
| @@ -51,10 +54,17 @@ endif() | ||||
| # Install Python scripts, configuration files, and launch files | ||||
| if($ENV{ROS_VERSION} EQUAL "1") | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_prediction.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_object_detection.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_instance_segmentation.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_semantic_segmentation.py DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||||
|     install(DIRECTORY config/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) | ||||
|     install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) | ||||
| elseif($ENV{ROS_VERSION} EQUAL "2") | ||||
| else() | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_prediction.py DESTINATION lib/${PROJECT_NAME}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_object_detection.py DESTINATION lib/${PROJECT_NAME}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_instance_segmentation.py DESTINATION lib/${PROJECT_NAME}) | ||||
|     install(PROGRAMS src/bellande_3d_computer_vision_semantic_segmentation.py DESTINATION lib/${PROJECT_NAME}) | ||||
|     install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}/config) | ||||
|     install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch) | ||||
|     ament_package() | ||||
| endif() | ||||
|   | ||||
| @@ -12,7 +12,7 @@ def ros1_launch_description(): | ||||
|     args = sys.argv[1:] | ||||
|  | ||||
|     # Construct the ROS 1 launch commandi | ||||
|     roslaunch_command = ["roslaunch", "bellande_3d_computer_vision_prediction", "bellande_step_api_2d.launch"] + args | ||||
|     roslaunch_command = ["roslaunch", "ros_web_api_bellande_3d_computer_vision", "bellande_3d_computer_vision_prediction.launch"] + args | ||||
|  | ||||
|     # Execute the launch command | ||||
|     subprocess.call(roslaunch_command) | ||||
|   | ||||
| @@ -15,8 +15,21 @@ License for the specific language governing permissions and limitations under | ||||
| the License. | ||||
| --> | ||||
| <launch> | ||||
|   <node pkg="bellande_3d_computer_vision_prediction" | ||||
|     type="bellande_3d_computer_vision_prediction.py" | ||||
|     name="bellande_3d_computer_vision_prediction_node" output="screen"> | ||||
|   <!-- Launch the point cloud source (adjust parameters as needed) --> | ||||
|   <node name="pointcloud_publisher" pkg="ros_web_api_bellande_3d_computer_vision" | ||||
|     type="pointcloud_pradiction_node" | ||||
|     output="screen"> | ||||
|     <param name="frame_id" value="base_link" /> | ||||
|   </node> | ||||
|  | ||||
|   <!-- Launch the prediction node --> | ||||
|   <node name="pointcloud_prediction_node" pkg="ros_web_api_bellande_3d_computer_vision" | ||||
|     type="pointcloud_prediction_node.py" output="screen"> | ||||
|     <remap from="input_pointcloud" to="/pointcloud_topic" /> | ||||
|   </node> | ||||
|  | ||||
|   <!-- Launch RViz for visualization --> | ||||
|   <node name="rviz" pkg="rviz" type="rviz" | ||||
|     args="-d $(find ros_web_api_bellande_3d_computer_vision)/rviz/pointcloud_visualization.rviz" /> | ||||
|  | ||||
| </launch> | ||||
|   | ||||
| @@ -0,0 +1,215 @@ | ||||
| Panels: | ||||
|   - Class: rviz/Displays | ||||
|     Help Height: 78 | ||||
|     Name: Displays | ||||
|     Property Tree Widget: | ||||
|       Expanded: | ||||
|         - /Global Options1 | ||||
|         - /Status1 | ||||
|         - /PointCloud21 | ||||
|         - /PointCloud22 | ||||
|         - /PointCloud23 | ||||
|         - /MarkerArray1 | ||||
|       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: PointCloud2 | ||||
| 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 | ||||
|     - Alpha: 1 | ||||
|       Autocompute Intensity Bounds: true | ||||
|       Autocompute Value Bounds: | ||||
|         Max Value: 10 | ||||
|         Min Value: -10 | ||||
|         Value: true | ||||
|       Axis: Z | ||||
|       Channel Name: intensity | ||||
|       Class: rviz/PointCloud2 | ||||
|       Color: 255; 255; 255 | ||||
|       Color Transformer: Intensity | ||||
|       Decay Time: 0 | ||||
|       Enabled: true | ||||
|       Invert Rainbow: false | ||||
|       Max Color: 255; 255; 255 | ||||
|       Max Intensity: 4096 | ||||
|       Min Color: 0; 0; 0 | ||||
|       Min Intensity: 0 | ||||
|       Name: Original PointCloud | ||||
|       Position Transformer: XYZ | ||||
|       Queue Size: 10 | ||||
|       Selectable: true | ||||
|       Size (Pixels): 3 | ||||
|       Size (m): 0.00999999978 | ||||
|       Style: Flat Squares | ||||
|       Topic: /pointcloud_topic | ||||
|       Unreliable: false | ||||
|       Use Fixed Frame: true | ||||
|       Use rainbow: true | ||||
|       Value: true | ||||
|     - Alpha: 1 | ||||
|       Autocompute Intensity Bounds: true | ||||
|       Autocompute Value Bounds: | ||||
|         Max Value: 10 | ||||
|         Min Value: -10 | ||||
|         Value: true | ||||
|       Axis: Z | ||||
|       Channel Name: instance | ||||
|       Class: rviz/PointCloud2 | ||||
|       Color: 255; 255; 255 | ||||
|       Color Transformer: Intensity | ||||
|       Decay Time: 0 | ||||
|       Enabled: true | ||||
|       Invert Rainbow: false | ||||
|       Max Color: 255; 255; 255 | ||||
|       Max Intensity: 4096 | ||||
|       Min Color: 0; 0; 0 | ||||
|       Min Intensity: 0 | ||||
|       Name: Instance Segmentation | ||||
|       Position Transformer: XYZ | ||||
|       Queue Size: 10 | ||||
|       Selectable: true | ||||
|       Size (Pixels): 3 | ||||
|       Size (m): 0.00999999978 | ||||
|       Style: Flat Squares | ||||
|       Topic: /pointcloud_instance_segmentation_result | ||||
|       Unreliable: false | ||||
|       Use Fixed Frame: true | ||||
|       Use rainbow: true | ||||
|       Value: true | ||||
|     - Alpha: 1 | ||||
|       Autocompute Intensity Bounds: true | ||||
|       Autocompute Value Bounds: | ||||
|         Max Value: 10 | ||||
|         Min Value: -10 | ||||
|         Value: true | ||||
|       Axis: Z | ||||
|       Channel Name: semantic | ||||
|       Class: rviz/PointCloud2 | ||||
|       Color: 255; 255; 255 | ||||
|       Color Transformer: Intensity | ||||
|       Decay Time: 0 | ||||
|       Enabled: true | ||||
|       Invert Rainbow: false | ||||
|       Max Color: 255; 255; 255 | ||||
|       Max Intensity: 4096 | ||||
|       Min Color: 0; 0; 0 | ||||
|       Min Intensity: 0 | ||||
|       Name: Semantic Segmentation | ||||
|       Position Transformer: XYZ | ||||
|       Queue Size: 10 | ||||
|       Selectable: true | ||||
|       Size (Pixels): 3 | ||||
|       Size (m): 0.00999999978 | ||||
|       Style: Flat Squares | ||||
|       Topic: /pointcloud_semantic_segmentation_result | ||||
|       Unreliable: false | ||||
|       Use Fixed Frame: true | ||||
|       Use rainbow: true | ||||
|       Value: true | ||||
|     - Class: rviz/MarkerArray | ||||
|       Enabled: true | ||||
|       Marker Topic: /pointcloud_object_detection_result | ||||
|       Name: Object Detection | ||||
|       Namespaces: | ||||
|         {} | ||||
|       Queue Size: 100 | ||||
|       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 | ||||
| @@ -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_3d_computer_vision_prediction.py'], | ||||
|     scripts=['src/bellande_3d_computer_vision_prediction.py', 'src/bellande_3d_computer_vision_object_detection.py', 'src/bellande_3d_computer_vision_instance_segmentation.py', 'src/bellande_3d_computer_vision_semantic_segmentation.py'], | ||||
|     packages=['ros_web_api_bellande_3d_computer_vision'], | ||||
|     package_dir={'': 'src'}, | ||||
| ) | ||||
|   | ||||
| @@ -1,23 +1,99 @@ | ||||
| # Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande | ||||
| # | ||||
| # This program is free software: you can redistribute it and/or modify | ||||
| # it under the terms of the GNU General Public License as published by | ||||
| # the Free Software Foundation, either version 3 of the License, or | ||||
| # (at your option) any later version. | ||||
| # | ||||
| # This program is distributed in the hope that it will be useful, | ||||
| # but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||
| # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||
| # GNU General Public License for more details. | ||||
| # | ||||
| # You should have received a copy of the GNU General Public License | ||||
| # along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||
|  | ||||
| import json | ||||
| import os | ||||
| import requests | ||||
| import numpy as np | ||||
| import base64 | ||||
| from sensor_msgs.msg import PointCloud2 | ||||
| import sensor_msgs.point_cloud2 as pc2 | ||||
| from std_msgs.msg import String | ||||
|  | ||||
|  | ||||
| def pointcloud_prediction(cloud_msg): | ||||
|     points = np.array(list(pc2.read_points(cloud_msg, skip_nans=True, field_names=("x", "y", "z")))) | ||||
|      | ||||
|     # Convert pointcloud to base64 encoding | ||||
|     points_base64 = base64.b64encode(points.tobytes()).decode('utf-8') | ||||
|  | ||||
|     payload = { | ||||
|         "pointcloud": points_base64 | ||||
|     } | ||||
|  | ||||
|     headers = { | ||||
|         "Authorization": f"Bearer {api_access_key}" | ||||
|     } | ||||
|  | ||||
|     response = requests.post(api_url, json=payload, headers=headers) | ||||
|  | ||||
|     if response.status_code == 200: | ||||
|         result = response.json() | ||||
|         prediction = result['prediction'] | ||||
|         confidence = result['confidence'] | ||||
|         return String(f"Prediction: {prediction}, Confidence: {confidence:.2f}") | ||||
|     else: | ||||
|         print(f"Error: {response.status_code} - {response.text}") | ||||
|         return None | ||||
|  | ||||
|  | ||||
| def pointcloud_callback(msg): | ||||
|     prediction = pointcloud_prediction(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, api_access_key, 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']["prediction"] | ||||
|         endpoint_path = config['endpoint_path']["pointcloud_api"] | ||||
|         api_access_key = config["Bellande_Framework_Access_Key"] | ||||
|      | ||||
|     if ros_version == "1": | ||||
|         rospy.init_node('pointcloud_prediction_node', anonymous=True) | ||||
|         pub = rospy.Publisher('pointcloud_prediction_result', String, queue_size=10) | ||||
|         sub = rospy.Subscriber('input_pointcloud', PointCloud2, pointcloud_callback) | ||||
|     elif ros_version == "2": | ||||
|         rclpy.init() | ||||
|         node = rclpy.create_node('pointcloud_prediction_node') | ||||
|         pub = node.create_publisher(String, 'pointcloud_prediction_result', 10) | ||||
|         sub = node.create_subscription(PointCloud2, 'input_pointcloud', pointcloud_callback, 10) | ||||
|  | ||||
|     api_url = f"{url}{endpoint_path}" | ||||
|  | ||||
|     try: | ||||
|         print("Pointcloud 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 pointcloud 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") | ||||
| @@ -25,5 +101,4 @@ if __name__ == '__main__': | ||||
|         import rospy | ||||
|     elif ros_version == "2": | ||||
|         import rclpy | ||||
|  | ||||
|     main() | ||||
|   | ||||
		Reference in New Issue
	
	Block a user