Skip to content

Commit

Permalink
Initial import.
Browse files Browse the repository at this point in the history
  • Loading branch information
gavanderhoorn committed Mar 5, 2018
1 parent 3d535ec commit c2967ed
Show file tree
Hide file tree
Showing 5 changed files with 405 additions and 0 deletions.
37 changes: 37 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
cmake_minimum_required(VERSION 2.8.3)

project(moveit_mpp)

add_compile_options(-std=c++11)

find_package(
catkin
REQUIRED
COMPONENTS
moveit_core
moveit_ros_planning
pluginlib
roscpp
)


catkin_package(
INCLUDE_DIRS
include
LIBRARIES
${PROJECT_NAME}
CATKIN_DEPENDS
moveit_core
moveit_ros_planning
pluginlib
roscpp
)


include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME}_planner_manager src/mpp_planner_manager.cpp)
target_link_libraries(${PROJECT_NAME}_planner_manager ${catkin_LIBRARIES})
64 changes: 64 additions & 0 deletions include/moveit_mpp/mpp_planner_manager.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
/**
* Copyright (c) 2018, G.A. vd. Hoorn
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* @author G.A. vd. Hoorn
*/

#ifndef MOVEIT_MPP_PLANNER_MANAGER_H_
#define MOVEIT_MPP_PLANNER_MANAGER_H_

#include <moveit/planning_interface/planning_interface.h>
#include <ros/node_handle.h>
#include <pluginlib/class_loader.h>

#include <map>
#include <string>
#include <vector>

namespace moveit_mpp
{

class MultiPlannerPluginManager : public planning_interface::PlannerManager
{
public:
MultiPlannerPluginManager();
virtual ~MultiPlannerPluginManager();

bool initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns) override;

bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const override;

std::string getDescription() const override
{
return "Multi Planner Plugin";
}

void getPlanningAlgorithms(std::vector<std::string> &algs) const override;

planning_interface::PlanningContextPtr getPlanningContext(
const planning_scene::PlanningSceneConstPtr &planning_scene,
const planning_interface::MotionPlanRequest &req,
moveit_msgs::MoveItErrorCodes &error_code) const override;

protected:
ros::NodeHandle nh_;
ros::NodeHandle pnh_;
std::map<std::string, planning_interface::PlannerManagerPtr> planners_;
boost::shared_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planner_plugin_loader_;
};

}

#endif /* MOVEIT_MPP_PLANNER_MANAGER_H_ */
7 changes: 7 additions & 0 deletions mpp_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<library path="libmoveit_mpp_planner_manager">
<class name="moveit_mpp/MultiPlanner" type="moveit_mpp::MultiPlannerPluginManager" base_class_type="planning_interface::PlannerManager">
<description>
MoveIt multi-planner plugin.
</description>
</class>
</library>
25 changes: 25 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<package>
<name>moveit_mpp</name>
<version>0.1.0</version>
<description>Multi-planner plugin hoster plugin for MoveIt</description>
<author>G.A. vd. Hoorn (TU Delft Robotics Institute)</author>
<maintainer email="[email protected]">G.A. vd. Hoorn (TU Delft Robotics Institute)</maintainer>
<license>Apache2</license>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>moveit_core</build_depend>
<build_depend>moveit_ros_planning</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>roscpp</build_depend>

<run_depend>moveit_core</run_depend>
<run_depend>moveit_ros_planning</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>roscpp</run_depend>

<export>
<moveit_core plugin="${prefix}/mpp_plugin_description.xml"/>
</export>
</package>
Loading

0 comments on commit c2967ed

Please sign in to comment.