Skip to content

Commit

Permalink
progress
Browse files Browse the repository at this point in the history
  • Loading branch information
pabloinigoblasco committed Nov 28, 2024
1 parent e2d79b1 commit c28c341
Show file tree
Hide file tree
Showing 3 changed files with 128 additions and 46 deletions.
93 changes: 61 additions & 32 deletions src/image_object_detection/image_object_detection_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -137,19 +137,75 @@ def __init__(self):

self.bridge = cv_bridge.CvBridge()

# Get the list of camera topics from the config file
self.declare_parameter("camera_topics", ["/cameras/frontleft_fisheye_image/image", "/cameras/frontright_fisheye_image/image", "/cameras/left_fisheye_image/image", "/cameras/right_fisheye_image/image"])
# Initialize camera topics parameter
self.declare_parameter("camera_topics", [
"/cameras/frontleft_fisheye_image/image",
"/cameras/frontright_fisheye_image/image",
"/cameras/left_fisheye_image/image",
"/cameras/right_fisheye_image/image"
])
self.camera_topics = self.get_parameter("camera_topics").get_parameter_value().string_array_value

self.get_logger().info(f"Subscribed to topics: {self.camera_topics}")

# Initialize subscribers and publishers for each camera topic
# Initialize empty containers for subscribers and publishers
self.subscribers = []
self.detection_publishers = {}
self.debug_image_publishers = {}

# Set up camera topics using the extracted method
self.setup_camera_topics()

self.initialize_model()

def parameters_callback(self, params):
result = SetParametersResult(successful=True)

init_model = False
for param in params:
if param.name == 'camera_topics':
self.camera_topics = param.value
self.get_logger().info(f"Updated camera_topics: {self.camera_topics}")
# Recreate subscribers and publishers for new topics
self.setup_camera_topics()

elif param.name == 'selected_detections':
self.selected_detections = param.value
self.get_logger().info(f"Updated selected_detections: {self.selected_detections}")

elif param.name == 'model.iou_threshold':
self.iou_threshold = param.value
self.get_logger().info(f"Updated iou_threshold: {self.iou_threshold}")

elif param.name == 'model.confidence':
self.confidence = param.value
self.get_logger().info(f"Updated confidence: {self.confidence}")

elif param.name == 'model.weights_file':
self.model_weights_file = param.value
self.get_logger().info(f"Updated weights_file: {self.model_weights_file}")
init_model = True

elif param.name == 'model.publish_debug_image':
self.enable_publish_debug_image = param.value
self.get_logger().info(f"Updated publish_debug_image: {self.enable_publish_debug_image}")
self.setup_camera_topics() # Recreate publishers with new debug setting

elif param.name == 'model.image_size':
self.model_image_size = param.value
self.get_logger().info(f"Updated image_size: {self.model_image_size}")
init_model = True

if init_model:
self.initialize_model()

return result
def setup_camera_topics(self):
# Clear existing subscribers and publishers
self.subscribers = []
self.detection_publishers = {}
self.debug_image_publishers = {}

for topic in self.camera_topics:
# Create a subscriber for each camera topic
self.subscribers.append(
self.create_subscription(
Image,
Expand All @@ -159,44 +215,17 @@ def __init__(self):
)
)

# Create a detection publisher for each camera
detection_topic = f"{topic}/detections"
self.detection_publishers[topic] = self.create_publisher(
Detection2DArray, detection_topic, self.qos
)

# Create a debug image publisher for each camera (if enabled)
if self.enable_publish_debug_image:
debug_image_topic = f"{topic}/debug_image"
self.debug_image_publishers[topic] = self.create_publisher(
Image, debug_image_topic, self.qos
)

self.initialize_model()
def parameters_callback(self, params):
result = SetParametersResult(successful=True)

for param in params:
if param.name == 'selected_detections':
self.selected_detections = param.value
self.get_logger().info(f"Updated selected_detections: {self.selected_detections}")

elif param.name == 'model.iou_threshold':
self.iou_threshold = param.value
self.get_logger().info(f"Updated iou_threshold: {self.iou_threshold}")

elif param.name == 'model.confidence':
self.confidence = param.value
self.get_logger().info(f"Updated confidence: {self.confidence}")

elif param.name == 'model.weights_file':
self.model_weights_file = param.value
self.get_logger().info(f"Updated weights_file: {self.model_weights_file}")
# Reinitialize model with new weights
self.initialize_model()

return result

def initialize_model(self):
with torch.no_grad():
set_logging()
Expand Down
45 changes: 42 additions & 3 deletions src/image_object_detection/templates/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,26 @@
border: 1px solid #ddd;
border-radius: 5px;
}
.video-grid {
display: grid;
grid-template-columns: repeat(2, 1fr);
gap: 20px;
margin: 20px;
}
.video-container {
border: 1px solid #ddd;
padding: 10px;
border-radius: 5px;
}
.video-container img {
width: 100%;
height: auto;
}
.video-title {
text-align: center;
margin-bottom: 10px;
font-weight: bold;
}
</style>
</head>
<body>
Expand Down Expand Up @@ -47,8 +67,27 @@ <h3>Detection Parameters</h3>
</div>
</div>

<button type="submit">Update Parameters</button>
</form>
<!-- Add this section after the other param sections -->
<div class="param-section">
<h3>Camera Topics</h3>
<div>
<textarea name="camera_topics" rows="5" style="width: 100%">{% for topic in camera_topics %}{{ topic }}
{% endfor %}</textarea>
<small>Enter one topic per line</small>
</div>
</div>

<button type="submit">Update Parameters</button>
</form>

<div class="video-grid">
{% for topic in camera_topics %}
<div class="video-container">
<div class="video-title">{{ topic }}</div>
<img src="http://localhost:8080/stream?topic={{ topic }}&type=mjpeg" alt="{{ topic }} stream">
</div>
{% endfor %}
</div>

<script>
document.getElementById('paramForm').onsubmit = function(e) {
Expand All @@ -66,4 +105,4 @@ <h3>Detection Parameters</h3>
};
</script>
</body>
</html>
</html>
36 changes: 25 additions & 11 deletions src/image_object_detection/web_interface_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,28 +11,32 @@ def __init__(self, detection_node):
self.app = Flask(__name__)
self.setup_routes()

# Start Flask in a separate thread
self.flask_thread = threading.Thread(target=self.run_flask)
self.flask_thread.daemon = True
self.flask_thread.start()

def setup_routes(self):
@self.app.route('/')
def index():
available_classes = self.detection_node.names
selected_classes = self.detection_node.selected_detections
current_confidence = self.detection_node.confidence
current_iou = self.detection_node.iou_threshold

return render_template('index.html',
available_classes=available_classes,
selected_classes=selected_classes,
confidence=current_confidence,
iou_threshold=current_iou)
available_classes=self.detection_node.names,
selected_classes=self.detection_node.selected_detections,
confidence=self.detection_node.confidence,
iou_threshold=self.detection_node.iou_threshold,
camera_topics=self.detection_node.camera_topics,
publish_debug_image=self.detection_node.enable_publish_debug_image,
image_size=self.detection_node.model_image_size)

@self.app.route('/update_params', methods=['POST'])
def update_params():
if request.method == 'POST':
# Handle camera topics
camera_topics = request.form.get('camera_topics', '').split('\n')
camera_topics = [topic.strip() for topic in camera_topics if topic.strip()]
self.detection_node.set_parameters([
Parameter('camera_topics', value=camera_topics)
])

# Handle selected detections
selected_classes = request.form.getlist('classes[]')
self.detection_node.set_parameters([
Expand All @@ -51,7 +55,17 @@ def update_params():
Parameter('model.iou_threshold', value=iou_threshold)
])

return jsonify({'status': 'success'})
# Add to existing parameter updates
publish_debug = request.form.get('publish_debug_image') == 'true'
self.detection_node.set_parameters([
Parameter('model.publish_debug_image', value=publish_debug)
])

image_size = int(request.form.get('image_size', 640))
self.detection_node.set_parameters([
Parameter('model.image_size', value=image_size)
])

return jsonify({'status': 'success'})
def run_flask(self):
self.app.run(host='0.0.0.0', port=5005)

0 comments on commit c28c341

Please sign in to comment.