diff --git a/CMakeLists.txt b/CMakeLists.txt index b303546fa7e74b4b8fab357cdd522626b6f29c49..7eae9c376b6a2fc7d9ddfa1686c5e6055f45dce8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,43 +1,101 @@ -cmake_minimum_required(VERSION 2.4.6) -include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) +cmake_minimum_required(VERSION 2.8.3) +project(iri_safe_cmd) -set(PROJECT_NAME safe_cmd_alg_node) +## Find catkin macros and libraries +find_package(catkin REQUIRED) +# ******************************************************************** +# Add catkin additional components here +# ******************************************************************** +find_package(catkin REQUIRED COMPONENTS geometry_msgs sensor_msgs iri_base_algorithm) -# Set the build type. Options are: -# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage -# Debug : w/ debug symbols, w/o optimization -# Release : w/o debug symbols, w/ optimization -# RelWithDebInfo : w/ debug symbols, w/ optimization -# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries -#set(ROS_BUILD_TYPE RelWithDebInfo) +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) -rosbuild_init() +# ******************************************************************** +# Add system and labrobotica dependencies here +# ******************************************************************** +find_package(iriutils REQUIRED) -#set the default path for built executables to the "bin" directory -set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) -#set the default path for built libraries to the "lib" directory -set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) +# ******************************************************************** +# Add topic, service and action definition here +# ******************************************************************** +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) -#uncomment if you have defined messages -#rosbuild_genmsg() -#uncomment if you have defined services -#rosbuild_gensrv() +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) -# added to include support for dynamic reconfiguration -rosbuild_find_ros_package(dynamic_reconfigure) -include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) -gencfg() -# end dynamic reconfiguration +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) -FIND_PACKAGE(iriutils REQUIRED) +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) -INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR} ./include) +# ******************************************************************** +# Add the dynamic reconfigure file +# ******************************************************************** +generate_dynamic_reconfigure_options(cfg/SafeCmd.cfg) -#common commands for building c++ executables and libraries -#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) -#target_link_libraries(${PROJECT_NAME} another_library) -#rosbuild_add_boost_directories() -#rosbuild_link_boost(${PROJECT_NAME} thread) -rosbuild_add_executable(${PROJECT_NAME} src/safe_cmd_alg.cpp src/safe_cmd_alg_node.cpp) +# ******************************************************************** +# Add run time dependencies here +# ******************************************************************** +catkin_package( +# INCLUDE_DIRS +# LIBRARIES +# ******************************************************************** +# Add ROS and IRI ROS run time dependencies +# ******************************************************************** + CATKIN_DEPENDS geometry_msgs sensor_msgs iri_base_algorithm +# ******************************************************************** +# Add system and labrobotica run time dependencies here +# ******************************************************************** + DEPENDS iriutils +) +########### +## Build ## +########### + +# ******************************************************************** +# Add the include directories +# ******************************************************************** +include_directories(include) +include_directories(${catkin_INCLUDE_DIRS}) +include_directories(${iriutils_INCLUDE_DIR}) + +## Declare a cpp library +# add_library(${PROJECT_NAME} <list of source files>) + +## Declare a cpp executable +add_executable(${PROJECT_NAME} src/safe_cmd_alg.cpp src/safe_cmd_alg_node.cpp) + +# ******************************************************************** +# Add the libraries +# ******************************************************************** +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARY}) + +# ******************************************************************** +# Add message headers dependencies +# ******************************************************************** +# add_dependencies(${PROJECT_NAME} <msg_package_name>_cpp) +# ******************************************************************** +# Add dynamic reconfigure dependencies +# ******************************************************************** +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS}) + diff --git a/Makefile b/Makefile deleted file mode 100644 index b75b928f20ef9ea4f509a17db62e4e31b422c27f..0000000000000000000000000000000000000000 --- a/Makefile +++ /dev/null @@ -1 +0,0 @@ -include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/cfg/safe_cmd_alg_config.cfg b/cfg/SafeCmd.cfg similarity index 95% rename from cfg/safe_cmd_alg_config.cfg rename to cfg/SafeCmd.cfg index 0857f1062ee0620abaa6ecd5e43f0dbe901fb876..d9b60690c1e92bdc9ae2ddd6207e396efe6607c5 100755 --- a/cfg/safe_cmd_alg_config.cfg +++ b/cfg/SafeCmd.cfg @@ -32,9 +32,8 @@ # Author: PACKAGE='iri_safe_cmd' -import roslib; roslib.load_manifest(PACKAGE) -from dynamic_reconfigure.parameter_generator import * +from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() diff --git a/manifest.xml b/manifest.xml deleted file mode 100644 index 601c54fe6274c4c26ead2b09b7d545dbea979790..0000000000000000000000000000000000000000 --- a/manifest.xml +++ /dev/null @@ -1,20 +0,0 @@ -<package> - <description brief="iri_safe_cmd"> - - This node takes the cmd_vel input and depending on front and/or rear LaserScan lectures - and the command, stops the platform or lets it go - - - </description> - <author>Maintained by IRI Robotics Lab, Marti Morta</author> - <license>LGPL</license> - <review status="unreviewed" notes=""/> - <url>http://ros.org/wiki/iri_safe_cmd</url> - <depend package="roscpp"/> - <depend package="iri_base_algorithm"/> - <depend package="geometry_msgs"/> - <depend package="sensor_msgs"/> - -</package> - - diff --git a/package.xml b/package.xml new file mode 100644 index 0000000000000000000000000000000000000000..12e961b157d7fd9d252c0214810d700838ebf970 --- /dev/null +++ b/package.xml @@ -0,0 +1,50 @@ +<?xml version="1.0"?> +<package> + <name>iri_safe_cmd</name> + <version>1.0.0</version> + <description>This node takes the cmd_vel input and depending on front and/or rear LaserScan lectures and the command, stops the platform or lets it go</description> + + <!-- One maintainer tag required, multiple allowed, one person per tag --> + <maintainer email="labrobotica@iri.upc.edu">labrobotica</maintainer> + <maintainer email="mmorta@iri.upc.edu">Marti Morta</maintainer> + + <!-- One license tag required, multiple allowed, one license per tag --> + <!-- Commonly used license strings: --> + <!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> + <license>LGPL</license> + + <!-- Url tags are optional, but mutiple are allowed, one per tag --> + <!-- Optional attribute type can be: website, bugtracker, or repository --> + <url type="website">http://wiki.ros.org/iri_safe_cmd</url> + + <!-- Author tags are optional, mutiple are allowed, one per tag --> + <!-- Authors do not have to be maintianers, but could be --> + <author email="mmorta@iri.upc.edu">Marti Morta</author> + + <!-- The *_depend tags are used to specify dependencies --> + <!-- Dependencies can be catkin packages or system dependencies --> + <!-- ****************************************************************** --> + <!-- Place build dependencies here --> + <!-- ****************************************************************** --> + <build_depend>iriutils</build_depend> + <build_depend>iri_base_algorithm</build_depend> + <build_depend>geometry_msgs</build_depend> + <build_depend>sensor_msgs</build_depend> + + <!-- ****************************************************************** --> + <!-- Place run dependencies here --> + <!-- ****************************************************************** --> + <run_depend>iriutils</run_depend> + <run_depend>iri_base_algorithm</run_depend> + <run_depend>geometry_msgs</run_depend> + <run_depend>sensor_msgs</run_depend> + + <!-- Use test_depend for packages you need only for testing: --> + <!-- <test_depend>gtest</test_depend> --> + <buildtool_depend>catkin</buildtool_depend> + + <!-- The export tag contains other, unspecified, tags --> + <export> + <!-- Other tools can request additional information be placed here --> + </export> +</package>