Skip to content

Commit

Permalink
Optional perception system (#62)
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam authored Jan 12, 2024
1 parent 4e80005 commit 67fa27f
Show file tree
Hide file tree
Showing 5 changed files with 56 additions and 25 deletions.
2 changes: 1 addition & 1 deletion rae_sdk/rae_sdk/robot/display.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ def hex_to_rgb(hex):
b_channel, g_channel, r_channel, alpha_channel = cv2.split(image)
# Define the color to replace the transparent parts (purple in this case)
# OpenCV uses BGR format, so purple is (128, 0, 128)
replacement_color = [r, g, b]
replacement_color = [b, g, r]
# Find all pixels where the alpha channel is zero
transparent_mask = alpha_channel < 150
# Set the color of these pixels to the replacement color
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
from geometry_msgs.msg import Twist, TransformStamped


class MovementController:
class NavigationController:
"""
A class for controlling the robot's movement.
Expand All @@ -19,7 +19,7 @@ class MovementController:
def __init__(self, ros_interface):
self._ros_interface = ros_interface
self._ros_interface.create_publisher("/cmd_vel", Twist)
log.info("Movement Controller ready")
log.info("Navigation Controller ready")

def move(self, linear, angular):
"""
Expand Down
43 changes: 21 additions & 22 deletions rae_sdk/rae_sdk/robot/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,11 @@
from .api.ros.ros_interface import ROSInterface
from .display import DisplayController
from .led import LEDController
from .movement import MovementController
from .navigation import NavigationController
from .audio import AudioController
from .state import StateController
from .perception.perception_system import PerceptionSystem
from .robot_options import RobotOptions
from sensor_msgs.msg import BatteryState


class Robot:
Expand All @@ -17,16 +17,15 @@ class Robot:
Attributes
----------
ros_interface (ROSInterface): An object for managing ROS2 communications and functionalities.
battery_state (BatteryState): Stores the current state of the robot's battery.
led_controller (LEDController): Controls the robot's LEDs.
display_controller (DisplayController): Manages the robot's display.
movement_controller (MovementController): Handles the robot's movement.
audio_controller (AudioController): Controls the robot's audio.
perception_system (PerceptionSystem): Handles the robot's perception system.
led (LEDController): Controls the robot's LEDs.
display (DisplayController): Manages the robot's display.
navigation (NavigationController): Handles the robot's movement.
audio (AudioController): Controls the robot's audio.
state (StateController): Manages the robot's state information.
perception (PerceptionSystem): Handles the robot's perception system.
Methods
-------
battery_state_cb(data): Callback method for updating battery state.
start(): Initializes the robot's components and starts ROS2 communications.
stop(): Stops the ROS2 communications and shuts down the robot's components.
Expand All @@ -47,12 +46,11 @@ def __init__(self, robot_options: RobotOptions = RobotOptions()):
if robot_options.launch_controllers:
self._led_controller = LEDController(self._ros_interface)
self._display_controller = DisplayController(self._ros_interface)
self._movement_controller = MovementController(self._ros_interface)
self._navigation_controller = NavigationController(self._ros_interface)
self._audio_controller = AudioController(self._ros_interface)
self._ros_interface.create_subscriber(
"/battery_status", BatteryState, self.battery_state_cb)
self._perception_system = PerceptionSystem(self._robot_options.namespace)
self._state_controller = StateController(self._ros_interface)

self._perception_system = None
log.info('Robot ready')

def __del__(self) -> None:
Expand All @@ -64,20 +62,21 @@ def stop(self):
Ensures a clean shutdown of all components.
"""
self._perception_system.stop()
if self._perception_system is not None:
self._perception_system.stop()
if self._display_controller is not None:
self._display_controller.stop()
self._ros_interface.stop()

def battery_state_cb(self, data):
self._battery_state = data

@property
def battery_state(self) -> BatteryState:
return self._battery_state
def state(self) -> StateController:
return self._state_controller

@property
def perception_system(self) -> PerceptionSystem:
def perception(self) -> PerceptionSystem:
"""Create perception system if it doesn't exist and return it."""
if self._perception_system is None:
self._perception_system = PerceptionSystem(self._robot_options.namespace)
return self._perception_system

@property
Expand All @@ -93,8 +92,8 @@ def display(self) -> DisplayController:
return self._display_controller

@property
def movement(self) -> MovementController:
return self._movement_controller
def navigation(self) -> NavigationController:
return self._navigation_controller

@property
def audio(self) -> AudioController:
Expand Down
1 change: 1 addition & 0 deletions rae_sdk/rae_sdk/robot/robot_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,3 +38,4 @@ def namespace(self):
@property
def launch_controllers(self):
return self._launch_controllers

31 changes: 31 additions & 0 deletions rae_sdk/rae_sdk/robot/state.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
import logging as log
from sensor_msgs.msg import BatteryState

class StateController:
"""
A class for managing the robot's state.
Attributes
----------
ros_interface (ROSInterface): An object for managing ROS2 communications and functionalities.
battery_state (BatteryState): Stores the current state of the robot's battery.
Methods
-------
battery_state_cb(data): Callback method for updating battery state.
"""

def __init__(self, ros_interface):
self._ros_interface = ros_interface
self._ros_interface.create_subscriber(
"/battery_status", BatteryState, self.battery_state_cb)
self._battery_state = None
log.info("State Controller ready")

def battery_state_cb(self, data):
self._battery_state = data

@property
def battery_state(self):
return self._battery_state

0 comments on commit 67fa27f

Please sign in to comment.