Skip to content
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

Robotx qual task #1272

Open
wants to merge 12 commits into
base: master
Choose a base branch
from
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
---
image_width: 1920
image_height: 1080
image_width: 640
image_height: 480
camera_name: head_camera
camera_matrix:
rows: 3
Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,18 @@
<?xml version="1.0"?>
<launch>
<arg name="simulation" default="False" />
<group ns="camera/front/right" >
<node pkg="usb_cam" type="usb_cam_node" name="dell_driver" unless="$(arg simulation)" >
<group ns="camera/front/right">
<node pkg="usb_cam" type="usb_cam_node" name="dell_driver" unless="$(arg simulation)">
<param name="video_device" value="/dev/v4l/by-id/usb-Alpha_Imaging_Tech._Corp._Dell_Webcam_WB7022_A7D19B26B27A-video-index0" />
<param name="camera_frame_id" value="wamv/front_right_cam_link_optical" />
<param name="camera_info_url" value="file://$(find navigator_launch)/config/camera_calibration/dell.yaml" />
<param name="pixel_format" value="yuyv" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="framerate" value="7" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="framerate" value="30" />
<remap from="dell_driver/image_raw" to="image_raw" />
<remap from="dell_driver/camera_info" to="camera_info" />
</node>
<node pkg="image_proc" type="image_proc" name="dell_right_image_proc">
</node>
<node pkg="image_proc" type="image_proc" name="dell_right_image_proc"></node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="front_left" default="True" />
<arg name="front_left" default="False" />
<arg name="front_right" default="True" />
<arg name="simulation" default="False" />
<include if="$(arg front_left)" file="$(find navigator_launch)/launch/hardware/cameras/dell_left.launch">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<node pkg="navigator_kill_board" type="kill_board_driver.py" name="kill_board_interface">
<param name="port" value="/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A104OWRY-if00-port0" />
<param name="port" value="/dev/serial/by-id/usb-Texas_Instruments_In-Circuit_Debug_Interface_0E237EF7-if00" />
<param name="baud" value="9700" />
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<include if="$(arg online-bagger)" file="$(find navigator_launch)/launch/online_bagger.launch" />
<include unless="$(arg simulation)" file="$(find navigator_launch)/launch/hardware.launch"/>
<include unless="$(arg simulation)" file="$(find navigator_launch)/launch/perception/classifier.launch" >
<arg name="main_image_topic" value="/camera/front/left/image_color"/>
<arg name="main_image_topic" value="/camera/front/right/image_color"/>
<arg name="use_yolo_model1" value="True"/>
<arg name="use_yolo_model2" value="False"/>
<arg name="weights_model1" value="$(find yolov7_ros)/src/mil_weights/robotx.pt" />
Expand Down
Original file line number Diff line number Diff line change
@@ -1,68 +1,67 @@
<?xml version="1.0"?>
<launch>

<arg name="weights_model1" default="$(find yolov7_ros)/src/mil_weights/robotx.pt" />
<arg name="weights_model2" default="$(find yolov7_ros)/src/mil_weights/robotx.pt" />
<arg name="weights_model3" default="$(find yolov7_ros)/src/mil_weights/stc.pt" />
<arg name="data_yaml_model1" default="$(find yolov7_ros)/src/data/vrx_buoys.yaml" />
<arg name="data_yaml_model2" default="$(find yolov7_ros)/src/data/vrx_buoys.yaml" />
<arg name="data_yaml_model3" default="$(find yolov7_ros)/src/data/stc.yaml" />
<arg name="main_image_topic" default="/camera/front/left/image_color"/>
<arg name="image_topic_model1" default="/yolov7/model1" />
<arg name="image_topic_model2" default="/yolov7/model2" />
<arg name="out_topic_model1" default="detections_model1" />
<arg name="out_topic_model2" default="detections_model2" />
<arg name="out_topic_model3" default="stc_detections_model" />
<arg name="conf_thresh" default="0.25" />
<arg name="image_size" default="640" />
<arg name="device" default="cpu" />
<arg name="use_yolo_model1" default="False"/>
<arg name="use_yolo_model2" default="False"/>
<arg name="use_yolo_model3" default="True"/>
<arg name="weights_model1" default="$(find yolov7_ros)/src/mil_weights/robotx.pt" />
<arg name="weights_model2" default="$(find yolov7_ros)/src/mil_weights/robotx.pt" />
<arg name="weights_model3" default="$(find yolov7_ros)/src/mil_weights/stc.pt" />
<arg name="data_yaml_model1" default="$(find yolov7_ros)/src/data/vrx_buoys.yaml" />
<arg name="data_yaml_model2" default="$(find yolov7_ros)/src/data/vrx_buoys.yaml" />
<arg name="data_yaml_model3" default="$(find yolov7_ros)/src/data/stc.yaml" />
<arg name="main_image_topic" default="/camera/front/right/image_color" />
<arg name="image_topic_model1" default="/yolov7/model1" />
<arg name="image_topic_model2" default="/yolov7/model2" />
<arg name="out_topic_model1" default="detections_model1" />
<arg name="out_topic_model2" default="detections_model2" />
<arg name="out_topic_model3" default="stc_detections_model" />
<arg name="conf_thresh" default="0.7" />
<arg name="image_size" default="640" />
<arg name="device" default="cpu" />
<arg name="use_yolo_model1" default="False" />
<arg name="use_yolo_model2" default="False" />
<arg name="use_yolo_model3" default="True" />

<node name="testing_arbiter" pkg="topic_tools" type="demux"
args="$(arg main_image_topic) $(arg image_topic_model1) $(arg image_topic_model2) /yolov7/none">
<remap from="demux" to="/yolov7"/>
</node>
<node name="testing_arbiter" pkg="topic_tools" type="demux" args="$(arg main_image_topic) $(arg image_topic_model1) $(arg image_topic_model2) /yolov7/none">
<remap from="demux" to="/yolov7" />
</node>

<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model1)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model1)"/>
<arg name="image_topic" value="$(arg image_topic_model1)"/>
<arg name="out_topic" value="$(arg out_topic_model1)"/>
<arg name="conf_thresh" value="$(arg conf_thresh)"/>
<arg name="image_size" value="$(arg image_size)"/>
<arg name="device" value="$(arg device)"/>
<arg name="data_yaml" value="$(arg data_yaml_model1)"/>
</include>
<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model1)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model1)" />
<arg name="image_topic" value="$(arg image_topic_model1)" />
<arg name="out_topic" value="$(arg out_topic_model1)" />
<arg name="conf_thresh" value="$(arg conf_thresh)" />
<arg name="image_size" value="$(arg image_size)" />
<arg name="device" value="$(arg device)" />
<arg name="data_yaml" value="$(arg data_yaml_model1)" />
</include>

<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model2)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model2)"/>
<arg name="image_topic" value="$(arg image_topic_model2)"/>
<arg name="out_topic" value="$(arg out_topic_model2)"/>
<arg name="conf_thresh" value="$(arg conf_thresh)"/>
<arg name="image_size" value="$(arg image_size)"/>
<arg name="device" value="$(arg device)"/>
<arg name="data_yaml" value="$(arg data_yaml_model2)"/>
</include>
<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model2)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model2)" />
<arg name="image_topic" value="$(arg image_topic_model2)" />
<arg name="out_topic" value="$(arg out_topic_model2)" />
<arg name="conf_thresh" value="$(arg conf_thresh)" />
<arg name="image_size" value="$(arg image_size)" />
<arg name="device" value="$(arg device)" />
<arg name="data_yaml" value="$(arg data_yaml_model2)" />
</include>

<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model3)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model3)"/>
<arg name="image_topic" value="/stc_mask_debug"/>
<arg name="out_topic" value="$(arg out_topic_model3)"/>
<arg name="conf_thresh" value="$(arg conf_thresh)"/>
<arg name="image_size" value="$(arg image_size)"/>
<arg name="device" value="$(arg device)"/>
<arg name="data_yaml" value="$(arg data_yaml_model3)"/>
</include>
<!-- Use YOLOv7 -->
<include if="$(arg use_yolo_model3)" file="$(find yolov7_ros)/launch/yolov7.launch">
<arg name="weights" value="$(arg weights_model3)" />
<arg name="image_topic" value="/stc_mask_debug" />
<arg name="out_topic" value="$(arg out_topic_model3)" />
<arg name="conf_thresh" value="$(arg conf_thresh)" />
<arg name="image_size" value="$(arg image_size)" />
<arg name="device" value="$(arg device)" />
<arg name="data_yaml" value="$(arg data_yaml_model3)" />
</include>

<arg name="train" default="False" />
<node pkg="navigator_vision" type="classifier.py" name="classifier" output="screen">
<param name="debug" value="True" />
<param name="image_topic" value="$(arg main_image_topic)" />
<param name="model_location" value="config/model" />
<param name="train" value="$(arg train)" />
</node>
<arg name="train" default="False" />
<node pkg="navigator_vision" type="classifier.py" name="classifier" output="screen">
<param name="debug" value="True" />
<param name="image_topic" value="$(arg main_image_topic)" />
<param name="model_location" value="config/model" />
<param name="train" value="$(arg train)" />
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -290,10 +290,18 @@ async def explore_closest_until(self, is_done, filter_and_sort):
# and find closest one within 25 meters (max width of a gate).
if cone_buoys_investigated > 0 and potential_candidate is None:
for i in range(len(objects)):
print(positions[i])
obj_vol = (
objects[i].scale.x * objects[i].scale.y * objects[i].scale.z
)

# Catch case where we invesitegate the shore
if obj_vol > 3:
continue

if (
objects[i].id not in investigated
and "round" not in objects[i].labeled_classification
and obj_vol < 3
):
distance = np.linalg.norm(positions[i] - self.pose[0])
if distance < shortest_distance and distance <= 25:
Expand All @@ -308,9 +316,18 @@ async def explore_closest_until(self, is_done, filter_and_sort):
# if that doesn't produce any results, literally just go to closest buoy
if potential_candidate is None:
for i in range(len(objects)):
obj_vol = (
objects[i].scale.x * objects[i].scale.y * objects[i].scale.z
)

# Catch case where we invesitegate the shore
if obj_vol > 3:
continue

if (
objects[i].id not in investigated
and "round" not in objects[i].labeled_classification
and obj_vol < 3
):
distance = np.linalg.norm(positions[i] - self.pose[0])
if distance < shortest_distance:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

import asyncio
import os
from enum import IntEnum
from typing import Callable

import genpy
Expand Down Expand Up @@ -42,6 +43,16 @@
from .pose_editor import PoseEditor2


class UAVModes(IntEnum):
"""
Enumerates constants of friendly uav mode names to ints
"""

STOWED = 1
DEPLOYED = 2
FAULTED = 3


class MissionResult:
NoResponse = 0
ParamNotFound = 1
Expand Down Expand Up @@ -130,6 +141,7 @@ async def setup_base(cls, mission_runner):
)

cls.pose = None
cls.uav_status = UAVModes.STOWED

def odom_set(odom: Odometry):
return setattr(cls, "pose", mil_tools.odometry_to_numpy(odom)[0])
Expand Down
Loading