Skip to content
Snippets Groups Projects
Commit f133d6a9 authored by Alejandro Suarez Hernandez's avatar Alejandro Suarez Hernandez
Browse files

Merge branch 'master' into gz7

parents 98399ce1 1211aed2
No related branches found
No related tags found
No related merge requests found
......@@ -7,11 +7,14 @@ add_definitions(-std=c++11)
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
actionlib
gazebo_plugins
gazebo_ros
iri_common_drivers_msgs
tf
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
......@@ -56,11 +59,10 @@ find_package(gazebo REQUIRED)
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
add_service_files(
FILES
CheckGrasped.srv
)
## Generate actions in the 'action' folder
# add_action_files(
......@@ -70,10 +72,10 @@ find_package(gazebo REQUIRED)
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# iri_common_drivers_msgs
# )
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
......@@ -107,7 +109,7 @@ find_package(gazebo REQUIRED)
catkin_package(
# INCLUDE_DIRS include
LIBRARIES gz_gripper_plugin
# CATKIN_DEPENDS actionlib gazebo_plugins gazebo_ros iri_common_drivers_msgs tf
CATKIN_DEPENDS actionlib gazebo_plugins gazebo_ros iri_common_drivers_msgs tf std_msgs message_runtime
# DEPENDS gazebo
)
......
......@@ -47,12 +47,16 @@
<build_depend>gazebo_ros</build_depend>
<build_depend>iri_common_drivers_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>actionlib</run_depend>
<run_depend>gazebo</run_depend>
<run_depend>gazebo_plugins</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>iri_common_drivers_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<!-- The export tag contains other, unspecified, tags -->
......
---
std_msgs/String grasped
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment