diff --git a/ws/src/frida_hri_interfaces/CMakeLists.txt b/ws/src/frida_hri_interfaces/CMakeLists.txt index bcf69a2..734786a 100644 --- a/ws/src/frida_hri_interfaces/CMakeLists.txt +++ b/ws/src/frida_hri_interfaces/CMakeLists.txt @@ -20,12 +20,14 @@ add_message_files( add_service_files( FILES Speak.srv + GuestInfo.srv ) ## Generate actions in the 'action' folder add_action_files( FILES Conversate.action + GuestAnalysis.action ) ## Generate added messages and services with any dependencies listed here diff --git a/ws/src/frida_hri_interfaces/action/GuestAnalysis.action b/ws/src/frida_hri_interfaces/action/GuestAnalysis.action new file mode 100644 index 0000000..0fa1d19 --- /dev/null +++ b/ws/src/frida_hri_interfaces/action/GuestAnalysis.action @@ -0,0 +1,9 @@ +#goal definition +int32 guest_id +--- +#result definition +int32 guest_id +string description +--- +#feedback +int32 feedback \ No newline at end of file diff --git a/ws/src/frida_hri_interfaces/srv/GuestInfo.srv b/ws/src/frida_hri_interfaces/srv/GuestInfo.srv new file mode 100644 index 0000000..b3e7fa9 --- /dev/null +++ b/ws/src/frida_hri_interfaces/srv/GuestInfo.srv @@ -0,0 +1,5 @@ +int32 guest_id +--- +bool success +string name +string favorite_drink \ No newline at end of file diff --git a/ws/src/frida_manipulation_interfaces/CMakeLists.txt b/ws/src/frida_manipulation_interfaces/CMakeLists.txt index 07c23dd..b0bac8b 100644 --- a/ws/src/frida_manipulation_interfaces/CMakeLists.txt +++ b/ws/src/frida_manipulation_interfaces/CMakeLists.txt @@ -14,10 +14,11 @@ find_package(catkin REQUIRED COMPONENTS message_generation ) -# add_service_files( -# FILES -# EnableOctomap.srv -# ) +add_service_files( + FILES + Gripper.srv +# EnableOctomap.srv +) # add_message_files( # FILES @@ -29,12 +30,14 @@ find_package(catkin REQUIRED COMPONENTS add_action_files( FILES manipulationPickAndPlace.action + MoveJoint.action ) generate_messages( DEPENDENCIES actionlib_msgs std_msgs + geometry_msgs ) catkin_package( diff --git a/ws/src/frida_manipulation_interfaces/action/MoveJoint.action b/ws/src/frida_manipulation_interfaces/action/MoveJoint.action new file mode 100644 index 0000000..42390fc --- /dev/null +++ b/ws/src/frida_manipulation_interfaces/action/MoveJoint.action @@ -0,0 +1,20 @@ +#goal definition +string predefined_position +int32 target_delta_x +int32 target_delta_y +float32[] joints_target +geometry_msgs/Pose pose_target +float32 speed +float32 acceleration +float32 position_tolerance +float32 orientation_tolerance +int32 planning_time +int32 num_planning_attempts +--- +#result definition +int32 success +float32 execution_time +--- +#feedback +string execution_state +float32 completion_percentage \ No newline at end of file diff --git a/ws/src/frida_manipulation_interfaces/srv/Gripper.srv b/ws/src/frida_manipulation_interfaces/srv/Gripper.srv new file mode 100644 index 0000000..f635203 --- /dev/null +++ b/ws/src/frida_manipulation_interfaces/srv/Gripper.srv @@ -0,0 +1,3 @@ +string state +--- +bool success \ No newline at end of file diff --git a/ws/src/frida_navigation_interfaces/CMakeLists.txt b/ws/src/frida_navigation_interfaces/CMakeLists.txt index 441dcd0..cd9602f 100644 --- a/ws/src/frida_navigation_interfaces/CMakeLists.txt +++ b/ws/src/frida_navigation_interfaces/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs + std_srvs ) @@ -19,6 +20,11 @@ add_action_files( navServ.action ) +add_service_files( + FILES + ViewAngle.srv +) + ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES diff --git a/ws/src/frida_navigation_interfaces/srv/ViewAngle.srv b/ws/src/frida_navigation_interfaces/srv/ViewAngle.srv new file mode 100644 index 0000000..c76be94 --- /dev/null +++ b/ws/src/frida_navigation_interfaces/srv/ViewAngle.srv @@ -0,0 +1,3 @@ +string text +--- +int16 angle \ No newline at end of file diff --git a/ws/src/frida_task_manager/scripts/hri_tasks.py b/ws/src/frida_task_manager/scripts/hri_tasks.py index d88606b..0eeeefe 100755 --- a/ws/src/frida_task_manager/scripts/hri_tasks.py +++ b/ws/src/frida_task_manager/scripts/hri_tasks.py @@ -12,9 +12,14 @@ from std_msgs.msg import String from frida_hri_interfaces.msg import ConversateAction, ConversateFeedback, ConversateGoal, ConversateResult from frida_hri_interfaces.srv import Speak +from frida_hri_interfaces.msg import GuestAnalysisAction, GuestAnalysisFeedback, GuestAnalysisGoal, GuestAnalysisResult +from frida_hri_interfaces.srv import GuestInfo, GuestInfoResponse SPEAK_TOPIC = "/speech/speak" +SPEAK_NOW_TOPIC = "/speech/speak_now" CONVERSATION_SERVER = "/conversation_as" +GUEST_INFO_SERVICE = "/guest_info" +GUEST_ANALYSIS_SERVER = "/guest_analysis_as" class TasksHRI: STATE_ENUM = { @@ -30,13 +35,16 @@ class TasksHRI: def __init__(self) -> None: self.conversation_client = actionlib.SimpleActionClient(CONVERSATION_SERVER, ConversateAction) - #self.pub_speak = rospy.Publisher(SPEAK_TOPIC, String, queue_size=10) + self.pub_speak = rospy.Publisher(SPEAK_NOW_TOPIC, String, queue_size=10) + try: rospy.wait_for_service(SPEAK_TOPIC, timeout=5.0) except rospy.ROSException: - rospy.logerr("Conversation service not available") + rospy.logerr("Speaker service not available") self.speak_client = rospy.ServiceProxy(SPEAK_TOPIC, Speak) + self.guest_description = ["", "", ""] + rospy.loginfo("HRI Task Manager initialized") def execute_command(self, command: str, complement: str, perceived_information: str) -> int: @@ -55,16 +63,54 @@ def execute_command(self, command: str, complement: str, perceived_information: #rospy.loginfo(f"Result: {result.success}") return result.success return 1 - + def cancel_command(self) -> None: """Method to cancel the current command""" self.conversation_client.cancel_all_goals() rospy.loginfo("Command canceled HRI") - def speak(self, text: str) -> None: + def get_guest_info(self, guest_id: int): + """Method to get the guest information + Returns the name and favorite drink of the guest""" + rospy.wait_for_service("/guest_info") + try: + guest_info = rospy.ServiceProxy(GUEST_INFO_SERVICE, GuestInfo) + response = guest_info(guest_id) + if response.success: + return response.name, response.favorite_drink + return "error", "error" + except rospy.ServiceException: + rospy.logerr("Service call failed") + return "error", "error" + + def analyze_guest(self, guest_id: int) -> str: + """Method to analyze the guest + Returns the guest name and favorite drink""" + client = actionlib.SimpleActionClient(GUEST_ANALYSIS_SERVER, GuestAnalysisAction) + client.wait_for_server() + + goal = GuestAnalysisGoal() + goal.guest_id = guest_id + client.send_goal( + goal, + done_cb=self.guest_analysis_done + ) + + def guest_analysis_done(self, status, result) -> None: + """Callback for the guest analysis""" + rospy.loginfo(f"Guest analysis result: {result.description}") + self.guest_description[result.guest_id] = result.description + + def get_guest_description(self, guest_id: int) -> str: + """Method to get the guest description stored""" + return self.guest_description[guest_id] + + def speak(self, text: str, now: bool = False) -> None: """Method to publish directly text to the speech node""" - #self.pub_speak.publish(text) - self.speak_client(text) + if now: + self.pub_speak.publish(text) + else: + self.speak_client(text) if __name__ == "__main__": try: diff --git a/ws/src/frida_task_manager/scripts/manipulation_tasks.py b/ws/src/frida_task_manager/scripts/manipulation_tasks.py index ee9348f..0b6b504 100644 --- a/ws/src/frida_task_manager/scripts/manipulation_tasks.py +++ b/ws/src/frida_task_manager/scripts/manipulation_tasks.py @@ -12,9 +12,12 @@ from std_msgs.msg import String, Int32 from frida_hri_interfaces.msg import Command, CommandList from frida_manipulation_interfaces.msg import manipulationPickAndPlaceAction, manipulationPickAndPlaceGoal, manipulationPickAndPlaceResult, manipulationPickAndPlaceFeedback +from frida_manipulation_interfaces.msg import MoveJointAction, MoveJointFeedback, MoveJointGoal, MoveJointResult MANIPULATION_SERVER = "/manipulationServer" +ARM_JOINTS_SERVER = "/arm_joints_as" PLACE_TARGET = -5 +POUR_TARGET = -10 class TasksManipulation: """Manager for the manipulation area tasks""" @@ -36,8 +39,12 @@ class TasksManipulation: def __init__(self) -> None: self.manipulation_client = actionlib.SimpleActionClient(MANIPULATION_SERVER, manipulationPickAndPlaceAction) + self.arm_joints_client = actionlib.SimpleActionClient(ARM_JOINTS_SERVER, MoveJointAction) + if not self.manipulation_client.wait_for_server(timeout=rospy.Duration(10.0)): rospy.logerr("Manipulation server not initialized") + if not self.arm_joints_client.wait_for_server(timeout=rospy.Duration(10.0)): + rospy.logerr("Arm joints server not initialized") rospy.loginfo("Manipulation Task Manager initialized") @@ -73,6 +80,15 @@ def manipulation_goal_feedback(feedback_msg): self.manipulation_client.wait_for_result() result = self.manipulation_client.get_result() return TasksManipulation.STATE["EXECUTION_SUCCESS"] if result.result else TasksManipulation.STATE["EXECUTION_ERROR"] + + def move_arm_joints(self, target_x: int, target_y: int) -> int: + """Method to move the arm joints""" + self.arm_joints_client.send_goal( + MoveJointGoal(target_delta_x = target_x, target_delta_y = target_y) + ) + self.arm_joints_client.wait_for_result() + result = self.arm_joints_client.get_result() + return TasksManipulation.STATE["EXECUTION_SUCCESS"] if result.success else TasksManipulation.STATE["EXECUTION_ERROR"] def cancel_command(self) -> None: """Method to cancel the current command""" diff --git a/ws/src/frida_task_manager/scripts/receptionist_task_manager.py b/ws/src/frida_task_manager/scripts/receptionist_task_manager.py new file mode 100755 index 0000000..e759cef --- /dev/null +++ b/ws/src/frida_task_manager/scripts/receptionist_task_manager.py @@ -0,0 +1,227 @@ +#!/usr/bin/env python3 + +""" +Task manager for the Breakfast task of RoboCup @Home 2024 +""" + +### Import libraries +import rospy +import actionlib + +### ROS messages +from std_msgs.msg import String +from frida_vision_interfaces.msg import Person, PersonList +from frida_hri_interfaces.msg import Command, CommandList +from frida_hri_interfaces.msg import GuestAnalysisAction, GuestAnalysisFeedback, GuestAnalysisGoal, GuestAnalysisResult +from frida_hri_interfaces.srv import GuestInfo, GuestInfoResponse + +### Python submodules +from hri_tasks import TasksHRI +from manipulation_tasks import TasksManipulation +from nav_tasks import TasksNav +from vision_tasks import TasksVision + +SPEAK_TOPIC = "/speech/speak" +CONVERSATION_SERVER = "/conversation_as" +FACE_LOCATIONS_TOPIC = "/person_list" + +NAV_ENABLED = True +MANIPULATION_ENABLED = True +CONVERSATION_ENABLED = True +VISION_ENABLED = True + +AREAS = ["nav", "manipulation", "hri", "vision"] + +AREA_ENABLED = { + "nav": NAV_ENABLED, + "manipulation": MANIPULATION_ENABLED, + "hri": CONVERSATION_ENABLED, + "vision": VISION_ENABLED +} + +STATES = { + "WAITING_GUEST": 0, + "SELF_INTRODUCTION": 1, + "REQUEST_GUEST_INFORMATION": 2, + "SAVE_USER_FACE": 3, + "GO_TO_LIVING_ROOM": 4, + "INTRODUCE_PEOPLE_TO_GUEST": 5, + "GAZE_AT_GUEST": 6, + "FIND_FREE_SEAT": 7, + "GAZE_AT_SEAT": 8, + "GO_TO_ENTRANCE": 9, + "ERROR": 20, + "SHUTDOWN": 100 +} + +class Guest: + """Class to store the information of the guest""" + def __init__(self, guest_id: int = 0, name: str = "", favorite_drink: str = "", description: str = "") -> None: + self.guest_id = guest_id + self.name = name + self.favorite_drink = favorite_drink + self.description = description + def set_info(self, name: str, favorite_drink: str) -> None: + self.name = name + self.favorite_drink = favorite_drink + def set_description(self, description: str) -> None: + self.description = description + +class ReceptionistTaskManager: + """Class to manage different tasks divided by categories""" + COMMANDS_CATEGORY = { + "nav" : ["go", "follow", "stop", "approach", "remember"], + "manipulation" : ["pick", "place", "grasp", "give", "open", "close", "pour"], + "hri" : ["ask", "interact", "feedback"], + "vision" : ["find", "identify", "count", "wait"] + } + + def __init__(self) -> None: + self._node = rospy.init_node("task_manager_server") + self._rate = rospy.Rate(200) + + self.last_time = rospy.Time.now() + self.follow_sample_time = 0.5 + + # Creates an empty dictionary to store the subtask manager of each area + self.subtask_manager = dict.fromkeys(AREAS, None) + + if CONVERSATION_ENABLED: + self.subtask_manager["hri"] = TasksHRI() + if MANIPULATION_ENABLED: + self.subtask_manager["manipulation"] = TasksManipulation() + if NAV_ENABLED: + self.subtask_manager["nav"] = TasksNav() + if VISION_ENABLED: + self.subtask_manager["vision"] = TasksVision() + rospy.Subscriber(FACE_LOCATIONS_TOPIC, PersonList, self.get_face_locations) + + self.current_state = STATES["WAITING_GUEST"] + self.current_past_state = None + self.current_command = None + self.current_queue = [] + self.perceived_information = "" + + self.detected_faces = [] + self.following_face = True + self.followed_person = "Unknown" + self.arm_moving = False + + self.current_guest = 1 + + self.guests = [ + Guest(0, "Adan", "beer", "Is wearing glasses, has dark brown hair, a blue t-shirt and shorts."), + Guest(1), + Guest(2), + ] + + self.run() + + def get_face_locations(self, data: PersonList) -> None: + """Callback to receive the face locations""" + self.detected_faces = data.list + + def follow_face(self) -> bool: + """Calls the arm joints server to follow a face + Returns: Movement of the arm executed""" + if self.following_face and not self.arm_moving and self.detected_faces: + rospy.loginfo(f"Following {self.followed_person}") + self.arm_moving = True + for face in self.detected_faces: + if face.name == self.followed_person: + self.subtask_manager["manipulation"].move_arm_joints(face.x, face.y) + self.arm_moving = False + self.detected_faces = [] + return True + return False + + def execute_command(self, command: Command) -> int: + """Method for executing a single command inside its area submodule""" + + rospy.loginfo(f"Executing command: {command.action} -> {command.complement}") + + task_result = 0 + for area in AREAS: + if command.action in ReceptionistTaskManager.COMMANDS_CATEGORY[area] and AREA_ENABLED[area]: + task_result = self.subtask_manager[area].execute_command( + command.action, command.complement, self.perceived_information + ) + + if task_result == -1: + rospy.logerr("Error in task execution") + return STATES["ERROR"] + + self.perceived_information += f"{command.action} {command.complement} {task_result} " + return STATES["EXECUTING_COMMANDS"] + + def cancel_command(self) -> None: + """Method to cancel the current command""" + for area in AREAS: + if self.current_command in ReceptionistTaskManager.COMMANDS_CATEGORY[area]: + self.subtask_manager[area].cancel_command() + + def run(self) -> None: + """Main loop for the task manager""" + while not rospy.is_shutdown(): + dt = rospy.Time.now() - self.last_time # Time from last iteration + + if self.current_state == STATES["WAITING_GUEST"]: + if dt.to_sec() > self.follow_sample_time: + self.last_time = rospy.Time.now() + if self.follow_face(): + self.current_state = STATES["SELF_INTRODUCTION"] + + ### Self introduction + elif self.current_state == STATES["SELF_INTRODUCTION"]: + self.subtask_manager["hri"].speak("Hi, my name is Frida. I'll be your receptionist today.", now=False) + self.current_state = STATES["REQUEST_GUEST_INFORMATION"] + + ### Request name and favorite drink and store in current guest object + elif self.current_state == STATES["REQUEST_GUEST_INFORMATION"]: + self.subtask_manager["hri"].speak("Could you tell me your name and your favorite drink?", now=False) + name, drink = self.subtask_manager["hri"].get_guest_info( self.current_guest ) + self.guests[self.current_guest].set_info(name, drink) + if name != "error": + self.subtask_manager["hri"].speak(f"Nice to meet you {name}, please stay in front of me while I recognize your face.", now=False) + self.current_state = STATES["SAVE_USER_FACE"] + else: + self.subtask_manager["hri"].speak("I'm sorry, I didn't get your information.", now=False) + + ### Store user face with its name and call image analysis + elif self.current_state == STATES["SAVE_USER_FACE"]: + if self.follow_face(): + self.subtask_manager["hri"].analyze_guest( self.current_guest ) + self.subtask_manager["vision"].save_face_name( self.guests[self.current_guest].name ) + self.subtask_manager["hri"].speak("I have saved your face, thank you. Please follow me to the living room.", now=False) + self.current_state = STATES["GO_TO_LIVING_ROOM"] + else: + self.subtask_manager["hri"].speak("I'm sorry, I couldn't recognize your face. Please stay in front of me.", now=False) + + ### Navigate to the living room + elif self.current_state == STATES["GO_TO_LIVING_ROOM"]: + self.subtask_manager["nav"].execute_command("remember", "past location", "") + self.subtask_manager["hri"].speak("The host is already waiting for you there.", now=True) + #self.subtask_manager["manipulation"].move_arm_joints(500, 0) + #TODO: Face to front default arm position with arm server + self.subtask_manager["nav"].execute_command("go", "soccer", "") + self.current_state = STATES["INTRODUCE_PEOPLE_TO_GUEST"] + + ### Introduce people to the guest + elif self.current_state == STATES["INTRODUCE_PEOPLE_TO_GUEST"]: + self.followed_person = self.guests[0].name + self.follow_face() + self.subtask_manager["hri"].speak(f"This is {self.guests[0].name}.", now=False) + self.subtask_manager["hri"].speak(f"It's favorite drink is {self.guests[0].favorite_drink}.", now=False) + #self.guests[1].set_description( self.subtask_manager["hri"].get_guest_description( self.current_guest ) ) + #TODO: Extract interpreted info + self.subtask_manager["hri"].speak(f"{self.guests[0].description}", now=False) + self.current_state = STATES["GAZE_AT_GUEST"] + + self._rate.sleep() + + +if __name__ == "__main__": + try: + ReceptionistTaskManager() + except rospy.ROSInterruptException as e: + rospy.logerr(f'Error: {e}') diff --git a/ws/src/frida_task_manager/scripts/vision_tasks.py b/ws/src/frida_task_manager/scripts/vision_tasks.py new file mode 100644 index 0000000..09e53e8 --- /dev/null +++ b/ws/src/frida_task_manager/scripts/vision_tasks.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python3 + +""" +This script manages the implementation of each Nav tasks +""" + +### Import libraries +import rospy +import actionlib + +### ROS messages +from std_msgs.msg import String +from frida_vision_interfaces.srv import NewHost, NewHostResponse + +STORE_FACE_SERVICE = "/new_name" + +class TasksVision: + """Class to manage the navigation tasks""" + STATE = { + "TERMINAL_ERROR": -1, + "EXECUTION_ERROR": 0, + "EXECUTION_SUCCESS": 1 + } + + AREA_TASKS = ["wait", "save"] + + def __init__(self) -> None: + """Initialize the ROS node""" + self.save_name_call = rospy.ServiceProxy(STORE_FACE_SERVICE, NewHost) + + self.save_name_call.wait_for_service(timeout=rospy.Duration(10.0)) + + rospy.loginfo("Vision Task Manager initialized") + + def execute_command(self, command: str, target: str, info: str) -> int: + """Method to execute each command""" + rospy.loginfo("Nav Command") + + return TasksVision.STATE["EXECUTION_ERROR"] + + def save_face_name(self, name: str) -> int: + """Method to save the face name""" + rospy.loginfo("Save face name") + try: + response = self.save_name_call( name ) + if response.success: + return TasksVision.STATE["EXECUTION_SUCCESS"] + except rospy.ServiceException: + rospy.logerr("Service call name failed") + + return TasksVision.STATE["EXECUTION_ERROR"] + + def cancel_command(self) -> None: + """Method to cancel the current command""" + rospy.loginfo("Command canceled Nav") + +if __name__ == "__main__": + try: + TasksVision() + except rospy.ROSInterruptException as e: + rospy.logerr(f'Error: {e}') diff --git a/ws/src/frida_vision_interfaces/CMakeLists.txt b/ws/src/frida_vision_interfaces/CMakeLists.txt new file mode 100644 index 0000000..79d7e76 --- /dev/null +++ b/ws/src/frida_vision_interfaces/CMakeLists.txt @@ -0,0 +1,62 @@ +cmake_minimum_required(VERSION 3.0.2) +project(frida_vision_interfaces) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + actionlib_msgs + actionlib + geometry_msgs + std_msgs + std_srvs + message_generation +) + + +add_message_files( + FILES + Person.msg + PersonList.msg +) + +## Generate services in the 'srv' folder +add_service_files( + FILES + NewHost.srv +) + +# Generate actions in the 'action' folder +add_action_files( + FILES + DetectPointingObject.action +) + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs + geometry_msgs + actionlib_msgs +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES frida_vision_interfaces +CATKIN_DEPENDS geometry_msgs message_generation std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include +# ${catkin_INCLUDE_DIRS} +) diff --git a/ws/src/frida_vision_interfaces/action/DetectPointingObject.action b/ws/src/frida_vision_interfaces/action/DetectPointingObject.action new file mode 100644 index 0000000..43f9cbb --- /dev/null +++ b/ws/src/frida_vision_interfaces/action/DetectPointingObject.action @@ -0,0 +1,17 @@ +#goal definition +string[] target_objects +int32 waiting_time +--- +#result definition +bool result +int32 label +string labelText +float32 score +float32 ymin +float32 xmin +float32 ymax +float32 xmax +geometry_msgs/PointStamped point3D +--- +#feedback +string status \ No newline at end of file diff --git a/ws/src/frida_vision_interfaces/msg/Person.msg b/ws/src/frida_vision_interfaces/msg/Person.msg new file mode 100644 index 0000000..d6f3d6e --- /dev/null +++ b/ws/src/frida_vision_interfaces/msg/Person.msg @@ -0,0 +1,3 @@ +string name +int64 x +int64 y \ No newline at end of file diff --git a/ws/src/frida_vision_interfaces/msg/PersonList.msg b/ws/src/frida_vision_interfaces/msg/PersonList.msg new file mode 100644 index 0000000..7c4fa17 --- /dev/null +++ b/ws/src/frida_vision_interfaces/msg/PersonList.msg @@ -0,0 +1 @@ +frida_vision_interfaces/Person[] list \ No newline at end of file diff --git a/ws/src/frida_vision_interfaces/package.xml b/ws/src/frida_vision_interfaces/package.xml new file mode 100644 index 0000000..b35167a --- /dev/null +++ b/ws/src/frida_vision_interfaces/package.xml @@ -0,0 +1,37 @@ + + + frida_vision_interfaces + 0.0.0 + The frida_vision_interfaces package + + + + + RoBorregos + + + + + + TODO + + + catkin + catkin + geometry_msgs + message_generation + std_msgs + geometry_msgs + std_msgs + message_generation + geometry_msgs + std_msgs + message_runtime + + + + + + + + diff --git a/ws/src/frida_vision_interfaces/srv/NewHost.srv b/ws/src/frida_vision_interfaces/srv/NewHost.srv new file mode 100644 index 0000000..dc5ebb7 --- /dev/null +++ b/ws/src/frida_vision_interfaces/srv/NewHost.srv @@ -0,0 +1,3 @@ +string name +--- +bool success \ No newline at end of file