Skip to content
This repository has been archived by the owner on Nov 13, 2017. It is now read-only.

Commit

Permalink
collapse OMPL plugin to one package
Browse files Browse the repository at this point in the history
  • Loading branch information
Ioan Sucan committed Apr 6, 2013
1 parent 71cdc9a commit 6b6dca1
Show file tree
Hide file tree
Showing 66 changed files with 103 additions and 191 deletions.
4 changes: 1 addition & 3 deletions moveit_planners/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
<description>Metapacakge that installs all available planners for MoveIt</description>
<author email="isucan@willowgarage.com">Ioan Sucan</author>
<author email="sachinc@willowgarage.com">Sachin Chitta</author>
<author email="gjones@willowgarage.com">Gil Jones</author>

<maintainer email="isucan@willowgarage.com">Ioan Sucan</maintainer>

Expand All @@ -14,8 +13,7 @@
<url type="bugtracker">https://github.com/ros-planning/moveit_planners/issues</url>
<url type="repository">https://github.com/ros-planning/moveit_planners</url>

<run_depend>moveit_ompl_planners_core</run_depend>
<run_depend>moveit_ompl_planners_ros_plugin</run_depend>
<run_depend>moveit_ompl_planners</run_depend>

<export>
<metapackage/>
Expand Down
25 changes: 19 additions & 6 deletions ompl/core/CMakeLists.txt → ompl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(moveit_ompl_planners_core)
project(moveit_ompl_planners)

if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release)
Expand All @@ -8,31 +8,44 @@ endif()
find_package(Eigen REQUIRED)
find_package(Boost REQUIRED system filesystem date_time thread serialization)
find_package(catkin REQUIRED COMPONENTS
moveit_core
moveit_core
moveit_ros_planning
roscpp
rosconsole
pluginlib
tf
dynamic_reconfigure
eigen_conversions
)

include(cmake/addOMPLDep.cmake.in)
find_package(OMPL REQUIRED)

generate_dynamic_reconfigure_options("ompl_interface/cfg/OMPLDynamicReconfigure.cfg")

catkin_package(
LIBRARIES
moveit_ompl_interface
${OMPL_LIBRARIES}
INCLUDE_DIRS
${OMPL_INCLUDE_DIRS}
ompl_interface/include
CATKIN_DEPENDS
moveit_core
CFG_EXTRAS
addOMPLDep.cmake)
)

include_directories(SYSTEM
${EIGEN_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS})

include_directories(ompl_interface/include
include_directories(${OMPL_INCLUDE_DIRS}
ompl_interface/include
${catkin_INCLUDE_DIRS})

link_directories(${catkin_LIBRARY_DIRS})
link_directories(${Boost_LIBRARY_DIRS})
link_directories(${OMPL_LIBRARY_DIRS})

add_subdirectory(ompl_interface)

install(FILES ompl_interface_plugin_description.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
8 changes: 0 additions & 8 deletions ompl/core/cmake/addOMPLDep.cmake.in

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
set(MOVEIT_LIB_NAME moveit_ompl_interface)

add_library(moveit_ompl_interface
add_library(${MOVEIT_LIB_NAME}
src/ompl_interface.cpp
src/planning_context_manager.cpp
src/constraints_library.cpp
Expand All @@ -20,15 +20,27 @@ add_library(moveit_ompl_interface
src/detail/constrained_valid_state_sampler.cpp
src/detail/constrained_goal_sampler.cpp
src/detail/ompl_console.cpp
src/ompl_interface_ros.cpp
)

find_package(OpenMP)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")

target_link_libraries(${MOVEIT_LIB_NAME} ${OMPL_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}")

catkin_add_gtest(test_state_space test/test_state_space.cpp)
target_link_libraries(test_state_space ${MOVEIT_LIB_NAME} ${OMPL_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
set_target_properties(test_state_space PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}")

install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib)
add_executable(moveit_ompl_planner src/ompl_planner.cpp)
target_link_libraries(moveit_ompl_planner ${MOVEIT_LIB_NAME})
set_target_properties(moveit_ompl_planner PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}")

add_library(moveit_ompl_planner_plugin src/ompl_plugin.cpp)
target_link_libraries(moveit_ompl_planner_plugin ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(TARGETS ${MOVEIT_LIB_NAME} moveit_ompl_planner moveit_ompl_planner_plugin
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
install(DIRECTORY include/ DESTINATION include)
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#!/usr/bin/env python
PACKAGE = "moveit_ompl_planners_ros_plugin"
PACKAGE = "moveit_ompl_planners"

from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,10 @@
#include <moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h>
#include <ros/ros.h>

namespace ompl_interface_ros
namespace ompl_interface
{
/** @class OMPLInterfaceROS */
class OMPLInterfaceROS : public ompl_interface::OMPLInterface
class OMPLInterfaceROS : public OMPLInterface
{
public:
/** @brief Constructor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,16 +34,16 @@

/* Author: Ioan Sucan, Sachin Chitta */

#include <moveit/ompl_interface_ros/ompl_interface_ros.h>
#include <moveit/ompl_interface/ompl_interface_ros.h>

ompl_interface_ros::OMPLInterfaceROS::OMPLInterfaceROS(const robot_model::RobotModelConstPtr &kmodel) :
ompl_interface::OMPLInterfaceROS::OMPLInterfaceROS(const robot_model::RobotModelConstPtr &kmodel) :
ompl_interface::OMPLInterface(kmodel),
nh_("~")
{
loadParams();
}

bool ompl_interface_ros::OMPLInterfaceROS::saveConstraintApproximations()
bool ompl_interface::OMPLInterfaceROS::saveConstraintApproximations()
{
std::string cpath;
if (nh_.getParam("constraint_approximations", cpath))
Expand All @@ -55,7 +55,7 @@ bool ompl_interface_ros::OMPLInterfaceROS::saveConstraintApproximations()
return false;
}

bool ompl_interface_ros::OMPLInterfaceROS::loadConstraintApproximations()
bool ompl_interface::OMPLInterfaceROS::loadConstraintApproximations()
{
std::string cpath;
if (nh_.getParam("constraint_approximations_path", cpath))
Expand All @@ -66,20 +66,20 @@ bool ompl_interface_ros::OMPLInterfaceROS::loadConstraintApproximations()
return false;
}

void ompl_interface_ros::OMPLInterfaceROS::loadConstraintSamplers()
void ompl_interface::OMPLInterfaceROS::loadConstraintSamplers()
{
constraint_sampler_manager_loader_.reset(new constraint_sampler_manager_loader::ConstraintSamplerManagerLoader(constraint_sampler_manager_));
}

void ompl_interface_ros::OMPLInterfaceROS::loadParams()
void ompl_interface::OMPLInterfaceROS::loadParams()
{
ROS_INFO("Initializing OMPL interface using ROS parameters");
loadPlannerConfigurations();
loadConstraintApproximations();
loadConstraintSamplers();
}

void ompl_interface_ros::OMPLInterfaceROS::loadPlannerConfigurations()
void ompl_interface::OMPLInterfaceROS::loadPlannerConfigurations()
{
const std::vector<std::string> &group_names = kmodel_->getJointModelGroupNames();
std::vector<ompl_interface::PlanningConfigurationSettings> pconfig;
Expand Down Expand Up @@ -193,7 +193,7 @@ void ompl_interface_ros::OMPLInterfaceROS::loadPlannerConfigurations()
setPlanningConfigurations(pconfig);
}

void ompl_interface_ros::OMPLInterfaceROS::printStatus()
void ompl_interface::OMPLInterfaceROS::printStatus()
{
ROS_INFO("OMPL ROS interface is running.");
}
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

/* Author: Ioan Sucan, Sachin Chitta */

#include <moveit/ompl_interface_ros/ompl_interface_ros.h>
#include <moveit/ompl_interface/ompl_interface_ros.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/robot_state/conversions.h>
#include <tf/transform_listener.h>
Expand Down Expand Up @@ -133,7 +133,7 @@ class OMPLPlannerService

ros::NodeHandle nh_;
planning_scene_monitor::PlanningSceneMonitor &psm_;
ompl_interface_ros::OMPLInterfaceROS ompl_interface_;
ompl_interface::OMPLInterfaceROS ompl_interface_;
ros::ServiceServer plan_service_;
ros::ServiceServer benchmark_service_;
ros::ServiceServer construct_ca_service_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,25 +32,25 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <moveit/ompl_interface_ros/ompl_interface_ros.h>
#include <moveit/ompl_interface/ompl_interface_ros.h>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_scene/planning_scene.h>
#include <boost/shared_ptr.hpp>
#include <class_loader/class_loader.h>

#include <dynamic_reconfigure/server.h>
#include "moveit_ompl_planners_ros_plugin/OMPLDynamicReconfigureConfig.h"
#include "moveit_ompl_planners/OMPLDynamicReconfigureConfig.h"

namespace ompl_interface_ros
namespace ompl_interface
{
using namespace moveit_ompl_planners_ros_plugin;
using namespace moveit_ompl_planners;

class OMPLPlanner : public planning_interface::Planner
{
public:

OMPLPlanner() : planning_interface::Planner(),
nh_("~")
nh_("~")
{
dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig>(ros::NodeHandle("~/ompl")));
dynamic_reconfigure_server_->setCallback(boost::bind(&OMPLPlanner::dynamicReconfigureCallback, this, _1, _2));
Expand Down Expand Up @@ -166,6 +166,6 @@ class OMPLPlanner : public planning_interface::Planner
std::string planner_data_link_name_;
};

} // ompl_interface_ros
} // ompl_interface

CLASS_LOADER_REGISTER_CLASS(ompl_interface_ros::OMPLPlanner, planning_interface::Planner);
CLASS_LOADER_REGISTER_CLASS(ompl_interface::OMPLPlanner, planning_interface::Planner);
6 changes: 6 additions & 0 deletions ompl/ompl_interface_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<library path="libmoveit_ompl_planner_plugin">
<class name="ompl_interface/OMPLPlanner" type="ompl_interface::OMPLPlanner" base_class_type="planning_interface::Planner">
<description>
</description>
</class>
</library>
11 changes: 7 additions & 4 deletions ompl/ros/package.xml → ompl/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<package>
<name>moveit_ompl_planners_ros_plugin</name>
<name>moveit_ompl_planners</name>
<version>0.3.7</version>
<description>MoveIt plugin for the OMPL interface</description>
<description>MoveIt interface to OMPL</description>
<author email="isucan@willowgarage.com">Ioan Sucan</author>
<maintainer email="isucan@willowgarage.com">Ioan Sucan</maintainer>

Expand All @@ -14,14 +14,17 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>moveit_core</build_depend>
<build_depend>ompl</build_depend>
<build_depend>eigen_conversions</build_depend>
<build_depend>moveit_ros_planning</build_depend>
<build_depend>moveit_ompl_planners_core</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>tf</build_depend>
<build_depend>pluginlib</build_depend>


<run_depend>moveit_core</run_depend>
<run_depend>ompl</run_depend>
<run_depend>moveit_ros_planning</run_depend>
<run_depend>moveit_ompl_planners_core</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
Expand All @@ -30,7 +33,7 @@
<run_depend>pluginlib</run_depend>

<export>
<moveit_core plugin="${prefix}/ompl_interface_ros_plugin_description.xml"/>
<moveit_core plugin="${prefix}/ompl_interface_plugin_description.xml"/>
</export>

</package>
4 changes: 0 additions & 4 deletions ompl/ros/.gitignore

This file was deleted.

44 changes: 0 additions & 44 deletions ompl/ros/CMakeLists.txt

This file was deleted.

15 changes: 0 additions & 15 deletions ompl/ros/ompl_interface_ros/CMakeLists.txt

This file was deleted.

Empty file.

0 comments on commit 6b6dca1

Please sign in to comment.