Skip to content

Commit

Permalink
Merge pull request #908 from tue-robotics/split_msgs
Browse files Browse the repository at this point in the history
split_msgs
  • Loading branch information
MatthijsBurgh committed Nov 26, 2019
2 parents 4c8fe7f + 100acf2 commit eb1d35a
Show file tree
Hide file tree
Showing 10 changed files with 60 additions and 162 deletions.
3 changes: 1 addition & 2 deletions challenge_manipulation/src/manipulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
import random

# ED
from ed_robocup.srv import FitEntityInImageRequest
from ed_robocup_msgs.srv import FitEntityInImage, FitEntityInImageRequest

# Robot Smach States
import robot_smach_states.util.designators as ds
Expand Down Expand Up @@ -202,7 +202,6 @@ def __init__(self, robot, entity_str):
smach.State.__init__(self, outcomes=['succeeded', 'failed'])

self._robot = robot
from ed_robocup.srv import FitEntityInImage
self._srv = rospy.ServiceProxy(robot.robot_name + '/ed/fit_entity_in_image', FitEntityInImage)
self._entity_str = entity_str

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import rospy
import smach
from ed_robocup.srv import FitEntityInImage, FitEntityInImageRequest
from ed_robocup_msgs.srv import FitEntityInImage, FitEntityInImageRequest


class FitEntity(smach.State):
""" Fits an entity """
Expand Down
14 changes: 0 additions & 14 deletions challenge_test/src/test_states.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,13 @@
# Date: October 2015
################################################

import roslib
import rospy
import smach
import subprocess
import inspect
import random
import ed_perception.msg
import math
import robot_skills.util.msg_constructors as msgs

from ed_msgs.msg import EntityInfo
from smach_ros import SimpleActionState
from collections import namedtuple
from dragonfly_speech_recognition.srv import GetSpeechResponse
from robot_smach_states.util.designators import *
from robot_smach_states.human_interaction.human_interaction import HearOptionsExtra
from robot_smach_states import Grab
from robocup_knowledge import load_knowledge
from robot_skills.util import transformations
from robot_skills.arms import Arm


# ----------------------------------------------------------------------------------------------------

Expand Down
75 changes: 18 additions & 57 deletions robot_skills/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,59 +2,34 @@ cmake_minimum_required(VERSION 2.8.3)
project(robot_skills)

find_package(catkin REQUIRED COMPONENTS
actionlib
amigo_msgs
cb_planner_msgs_srvs
control_msgs
cv_bridge
dragonfly_speech_recognition
ed_msgs
ed_gui_server_msgs
ed_navigation_msgs
ed_people_recognition_msgs
ed_perception_msgs
geometry_msgs
head_ref_msgs
people_recognition_msgs
rgbd_msgs
rospy
roscpp
smach
smach_ros
geometry_msgs
std_srvs
actionlib
text_to_speech
tf
amigo_msgs
tue_msgs
visualization_msgs
head_ref
control_msgs
trajectory_msgs
cb_planner_msgs_srvs
tue_manipulation_msgs
text_to_speech
ed_msgs
ed_navigation
dragonfly_speech_recognition
tue_msgs
visualization_msgs
)

catkin_python_setup()

# find_package(Boost REQUIRED COMPONENTS system program_options)
# find_package(PCL REQUIRED)
# find_package(OpenCV REQUIRED)

# ------------------------------------------------------------------------------------------------
# ROS MESSAGES AND SERVICES
# ------------------------------------------------------------------------------------------------

# Generate messages
# add_message_files(
# FILES
# message1.msg
# ...
# )

# Generate services
# add_service_files(
# FILES
# service1.srv
# ...
# )

# Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# geometry_msgs
# ...
# )

# ------------------------------------------------------------------------------------------------
# CATKIN EXPORT
# ------------------------------------------------------------------------------------------------
Expand All @@ -73,17 +48,3 @@ catkin_package(
include_directories(
${catkin_INCLUDE_DIRS}
)

# add_library(library_name
# src/lib_source_file1.cpp
# ...
# )
# target_link_libraries(library_name ${catkin_LIBRARIES})

# add_executable(exec_name
# src/source_file1.cpp
# ...
# )
# target_link_libraries(exec_name ${catkin_LIBRARIES})


103 changes: 27 additions & 76 deletions robot_skills/package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package>
<package format="2">
<name>robot_skills</name>
<version>0.0.0</version>
<description>No description available</description>
Expand All @@ -10,80 +10,31 @@

<buildtool_depend>catkin</buildtool_depend>

<run_depend>cv_bridge</run_depend>

<build_depend>rospy</build_depend>
<run_depend>rospy</run_depend>

<build_depend>roscpp</build_depend>
<run_depend>roscpp</run_depend>

<build_depend>smach</build_depend>
<run_depend>smach</run_depend>

<build_depend>smach_ros</build_depend>
<run_depend>smach_ros</run_depend>

<build_depend>geometry_msgs</build_depend>
<run_depend>geometry_msgs</run_depend>

<build_depend>std_srvs</build_depend>
<run_depend>std_srvs</run_depend>

<build_depend>actionlib</build_depend>
<run_depend>actionlib</run_depend>

<build_depend>tf</build_depend>
<run_depend>tf</run_depend>

<build_depend>amigo_msgs</build_depend>
<run_depend>amigo_msgs</run_depend>

<build_depend>tue_msgs</build_depend>
<run_depend>tue_msgs</run_depend>

<build_depend>visualization_msgs</build_depend>
<run_depend>visualization_msgs</run_depend>

<build_depend>head_ref</build_depend>
<run_depend>head_ref</run_depend>

<build_depend>control_msgs</build_depend>
<run_depend>control_msgs</run_depend>

<build_depend>trajectory_msgs</build_depend>
<run_depend>trajectory_msgs</run_depend>

<build_depend>cb_planner_msgs_srvs</build_depend>
<run_depend>cb_planner_msgs_srvs</run_depend>

<build_depend>dragonfly_speech_recognition</build_depend>
<run_depend>dragonfly_speech_recognition</run_depend>

<build_depend>tue_manipulation_msgs</build_depend>
<run_depend>tue_manipulation_msgs</run_depend>

<build_depend>text_to_speech</build_depend>
<run_depend>text_to_speech</run_depend>

<build_depend>ed_msgs</build_depend>
<run_depend>ed_msgs</run_depend>

<build_depend>ed_perception</build_depend>
<run_depend>ed_perception</run_depend>

<build_depend>ed_navigation</build_depend>
<run_depend>ed_navigation</run_depend>

<build_depend>ed_gui_server</build_depend>
<run_depend>ed_gui_server</run_depend>

<build_depend>ed_people_recognition_msgs</build_depend>
<run_depend>ed_people_recognition_msgs</run_depend>

<build_depend>people_recognition_msgs</build_depend>
<run_depend>people_recognition_msgs</run_depend>

<run_depend>python-mock</run_depend>
<depend>actionlib</depend>
<depend>amigo_msgs</depend>
<depend>cb_planner_msgs_srvs</depend>
<depend>control_msgs</depend>
<depend>cv_bridge</depend>
<depend>dragonfly_speech_recognition</depend>
<depend>ed_msgs</depend>
<depend>ed_gui_server_msgs</depend>
<depend>ed_navigation_msgs</depend>
<depend>ed_people_recognition_msgs</depend>
<depend>ed_perception_msgs</depend>
<depend>geometry_msgs</depend>
<depend>head_ref_msgs</depend>
<depend>people_recognition_msgs</depend>
<depend>rgbd_msgs</depend>
<depend>rospy</depend>
<depend>smach</depend>
<depend>std_srvs</depend>
<depend>text_to_speech</depend>
<depend>tf</depend>
<depend>trajectory_msgs</depend>
<depend>tue_manipulation_msgs</depend>
<depend>tue_msgs</depend>
<depend>visualization_msgs</depend>

<exec_depend>python-mock</exec_depend>

</package>
2 changes: 1 addition & 1 deletion robot_skills/src/robot_skills/head.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# ROS
import rospy
from geometry_msgs.msg import PointStamped
from head_ref.msg import HeadReferenceAction, HeadReferenceGoal
from head_ref_msgs.msg import HeadReferenceAction, HeadReferenceGoal

# TU/e Robotics
from robot_skills.robot_part import RobotPart
Expand Down
2 changes: 1 addition & 1 deletion robot_skills/src/robot_skills/mockbot.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
# TU/e Robotics
import arms
from ed_msgs.msg import EntityInfo
from ed_sensor_integration.srv import UpdateResponse
from ed_sensor_integration_msgs.srv import UpdateResponse
from robot_skills import robot
from robot_skills.util.kdl_conversions import VectorStamped, FrameStamped
from robot_skills.classification_result import ClassificationResult
Expand Down
2 changes: 1 addition & 1 deletion robot_skills/src/robot_skills/perception.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
# TU/e Robotics
from image_recognition_msgs.srv import Annotate, Recognize, RecognizeResponse, GetFaceProperties
from image_recognition_msgs.msg import Annotation
from rgbd.srv import Project2DTo3D
from rgbd_msgs.srv import Project2DTo3D
from robot_skills.robot_part import RobotPart
from robot_skills.util.kdl_conversions import VectorStamped
from robot_skills.util.image_operations import img_recognitions_to_rois, img_cutout
Expand Down
16 changes: 8 additions & 8 deletions robot_skills/src/robot_skills/world_model_ed.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@
# TU/e
import ed_msgs.srv
from ed_msgs.srv import SimpleQuery, SimpleQueryRequest, UpdateSrv, Configure
import ed_sensor_integration.srv
from ed_people_recognition_msgs.srv import EdRecognizePeople, EdRecognizePeopleRequest
from ed_perception.srv import Classify
from ed_gui_server.srv import GetEntityInfo, GetEntityInfoResponse
from ed_navigation.srv import GetGoalConstraint
import ed_sensor_integration_msgs.srv as ed_sensor_srv
from ed_people_recognition_msgs.srv import EdRecognizePeople
from ed_perception_msgs.srv import Classify
from ed_gui_server_msgs.srv import GetEntityInfo, GetEntityInfoResponse
from ed_navigation_msgs.srv import GetGoalConstraint
from cb_planner_msgs_srvs.msg import PositionConstraint

# Robot skills
Expand Down Expand Up @@ -57,14 +57,14 @@ def __init__(self, robot_name, tf_listener):
GetEntityInfo)
self._ed_update_srv = self.create_service_client('/%s/ed/update' % robot_name, UpdateSrv)
self._ed_kinect_update_srv = self.create_service_client('/%s/ed/kinect/update' % robot_name,
ed_sensor_integration.srv.Update)
ed_sensor_srv.Update)
self._ed_classify_srv = self.create_service_client('/%s/ed/classify' % robot_name, Classify)
self._ed_configure_srv = self.create_service_client('/%s/ed/configure' % robot_name, Configure)
self._ed_reset_srv = self.create_service_client('/%s/ed/reset' % robot_name, ed_msgs.srv.Reset)
self._ed_get_image_srv = self.create_service_client('/%s/ed/kinect/get_image' % robot_name,
ed_sensor_integration.srv.GetImage)
ed_sensor_srv.GetImage)
self._ed_ray_trace_srv = self.create_service_client('/%s/ed/ray_trace' % robot_name,
ed_sensor_integration.srv.RayTrace)
ed_sensor_srv.RayTrace)

self._ed_detect_people_srv = self.create_service_client('/%s/ed/people_recognition/detect_people' % robot_name,
EdRecognizePeople)
Expand Down
2 changes: 1 addition & 1 deletion robot_smach_states/test/test_world_model.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
import unittest
import PyKDL as kdl
from ed_sensor_integration.srv import UpdateResponse
from ed_sensor_integration_msgs.srv import UpdateResponse

from robot_skills import Mockbot
from robot_skills.classification_result import ClassificationResult
Expand Down

0 comments on commit eb1d35a

Please sign in to comment.