|
From: <is...@us...> - 2009-07-01 20:20:01
|
Revision: 18122
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18122&view=rev
Author: isucan
Date: 2009-07-01 20:19:58 +0000 (Wed, 01 Jul 2009)
Log Message:
-----------
renaming service name from KinematicPlan to MotionPlan
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl_planning/include/ompl_planning/RequestHandler.h
pkg/trunk/motion_planning/ompl_planning/mainpage.dox
pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp
pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
pkg/trunk/sandbox/chomp_motion_planner/include/chomp_motion_planner/chomp_planner_node.h
pkg/trunk/sandbox/chomp_motion_planner/src/chomp_planner_node.cpp
Added Paths:
-----------
pkg/trunk/motion_planning/motion_planning_srvs/srv/MotionPlan.srv
Removed Paths:
-------------
pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlan.srv
Deleted: pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlan.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlan.srv 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlan.srv 2009-07-01 20:19:58 UTC (rev 18122)
@@ -1,38 +0,0 @@
-# This service contains the definition for a request to the motion
-# planner and the output it provides
-
-# Parameters for the state space
-motion_planning_msgs/KinematicSpaceParameters params
-
-# Starting state updates. If certain joints should be considered
-# at positions other than the current ones, these positions should
-# be set here
-motion_planning_msgs/KinematicJoint[] start_state
-
-# The goal state for the model to plan for. The goal is achieved
-# if all constraints are satisfied
-motion_planning_msgs/KinematicConstraints goal_constraints
-
-# No state in the produced motion plan will violate these constraints
-motion_planning_msgs/KinematicConstraints path_constraints
-
-# The number of times this plan is to be computed. Shortest solution
-# will be reported.
-int32 times
-
-# The maximum amount of time the motion planner is allowed to plan for
-float64 allowed_time
-
----
-
-# A solution path, if found
-motion_planning_msgs/KinematicPath path
-
-# distance to goal as computed by the heuristic
-float64 distance
-
-# set to 1 if the computed path was approximate
-byte approximate
-
-# if state information was not up to date when planning, this is set to 1
-byte unsafe
Copied: pkg/trunk/motion_planning/motion_planning_srvs/srv/MotionPlan.srv (from rev 18088, pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlan.srv)
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/MotionPlan.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/MotionPlan.srv 2009-07-01 20:19:58 UTC (rev 18122)
@@ -0,0 +1,38 @@
+# This service contains the definition for a request to the motion
+# planner and the output it provides
+
+# Parameters for the state space
+motion_planning_msgs/KinematicSpaceParameters params
+
+# Starting state updates. If certain joints should be considered
+# at positions other than the current ones, these positions should
+# be set here
+motion_planning_msgs/KinematicJoint[] start_state
+
+# The goal state for the model to plan for. The goal is achieved
+# if all constraints are satisfied
+motion_planning_msgs/KinematicConstraints goal_constraints
+
+# No state in the produced motion plan will violate these constraints
+motion_planning_msgs/KinematicConstraints path_constraints
+
+# The number of times this plan is to be computed. Shortest solution
+# will be reported.
+int32 times
+
+# The maximum amount of time the motion planner is allowed to plan for
+float64 allowed_time
+
+---
+
+# A solution path, if found
+motion_planning_msgs/KinematicPath path
+
+# distance to goal as computed by the heuristic
+float64 distance
+
+# set to 1 if the computed path was approximate
+byte approximate
+
+# if state information was not up to date when planning, this is set to 1
+byte unsafe
Modified: pkg/trunk/motion_planning/ompl_planning/include/ompl_planning/RequestHandler.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/ompl_planning/RequestHandler.h 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/ompl_planning/include/ompl_planning/RequestHandler.h 2009-07-01 20:19:58 UTC (rev 18122)
@@ -39,7 +39,7 @@
#include "ompl_planning/Model.h"
#include <ros/ros.h>
-#include <motion_planning_srvs/KinematicPlan.h>
+#include <motion_planning_srvs/MotionPlan.h>
/** \brief Main namespace */
namespace ompl_planning
@@ -81,10 +81,10 @@
void disableDebugMode(void);
/** \brief Check if the request is valid */
- bool isRequestValid(ModelMap &models, motion_planning_srvs::KinematicPlan::Request &req);
+ bool isRequestValid(ModelMap &models, motion_planning_srvs::MotionPlan::Request &req);
/** \brief Check and compute a motion plan. Return true if the plan was succesfully computed */
- bool computePlan(ModelMap &models, const planning_models::StateParams *start, motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res);
+ bool computePlan(ModelMap &models, const planning_models::StateParams *start, motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res);
private:
@@ -98,13 +98,13 @@
/** \brief Set up all the data needed by motion planning based on a request and lock the planner setup
* using this data */
- void configure(const planning_models::StateParams *startState, motion_planning_srvs::KinematicPlan::Request &req, PlannerSetup *psetup);
+ void configure(const planning_models::StateParams *startState, motion_planning_srvs::MotionPlan::Request &req, PlannerSetup *psetup);
/** \brief Compute the actual motion plan. Return true if computed plan was trivial (start state already in goal region) */
bool callPlanner(PlannerSetup *psetup, int times, double allowed_time, Solution &sol);
/** \brief Fill the response with solution data */
- void fillResult(PlannerSetup *psetup, const planning_models::StateParams *start, motion_planning_srvs::KinematicPlan::Response &res, const Solution &sol);
+ void fillResult(PlannerSetup *psetup, const planning_models::StateParams *start, motion_planning_srvs::MotionPlan::Response &res, const Solution &sol);
/** \brief Send visualization markers */
void display(PlannerSetup *psetup);
Modified: pkg/trunk/motion_planning/ompl_planning/mainpage.dox
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/mainpage.dox 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/ompl_planning/mainpage.dox 2009-07-01 20:19:58 UTC (rev 18122)
@@ -78,7 +78,7 @@
\subsubsection services ROS services
-- @b "plan_kinematic_path"/KinematicPlan : given a robot model, starting and goal states,
+- @b "plan_kinematic_path"/MotionPlan : given a robot model, starting and goal states,
this service computes a collision free path.
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp 2009-07-01 20:19:58 UTC (rev 18122)
@@ -39,7 +39,7 @@
#include <ros/console.h>
#include <sstream>
-bool ompl_planning::RequestHandler::isRequestValid(ModelMap &models, motion_planning_srvs::KinematicPlan::Request &req)
+bool ompl_planning::RequestHandler::isRequestValid(ModelMap &models, motion_planning_srvs::MotionPlan::Request &req)
{
ModelMap::const_iterator pos = models.find(req.params.model_id);
@@ -114,7 +114,7 @@
return true;
}
-void ompl_planning::RequestHandler::configure(const planning_models::StateParams *startState, motion_planning_srvs::KinematicPlan::Request &req, PlannerSetup *psetup)
+void ompl_planning::RequestHandler::configure(const planning_models::StateParams *startState, motion_planning_srvs::MotionPlan::Request &req, PlannerSetup *psetup)
{
/* clear memory */
psetup->si->clearGoal();
@@ -194,7 +194,7 @@
}
bool ompl_planning::RequestHandler::computePlan(ModelMap &models, const planning_models::StateParams *start,
- motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+ motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
if (!isRequestValid(models, req))
return false;
@@ -236,7 +236,7 @@
return true;
}
-void ompl_planning::RequestHandler::fillResult(PlannerSetup *psetup, const planning_models::StateParams *start, motion_planning_srvs::KinematicPlan::Response &res, const Solution &sol)
+void ompl_planning::RequestHandler::fillResult(PlannerSetup *psetup, const planning_models::StateParams *start, motion_planning_srvs::MotionPlan::Response &res, const Solution &sol)
{
std::vector<planning_models::KinematicModel::Joint*> joints;
psetup->model->kmodel->getJoints(joints);
Modified: pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp 2009-07-01 20:19:58 UTC (rev 18122)
@@ -128,7 +128,7 @@
return NULL;
}
- bool planToGoal(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+ bool planToGoal(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
ROS_INFO("Received request for planning");
bool st = false;
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-07-01 20:19:58 UTC (rev 18122)
@@ -55,7 +55,7 @@
/** services **/
#include <sbpl_arm_planner_node/PlanPathSrv.h>
-#include <motion_planning_srvs/KinematicPlan.h>
+#include <motion_planning_srvs/MotionPlan.h>
namespace sbpl_arm_planner_node
{
@@ -70,7 +70,7 @@
~SBPLArmPlannerNode();
- bool planKinematicPath(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res);
+ bool planKinematicPath(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res);
private:
@@ -125,8 +125,8 @@
bool setGoalState(const std::vector<motion_planning_msgs::JointConstraint> &joint_constraint);
- bool planToState(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res);
- bool planToPosition(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res);
+ bool planToState(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res);
+ bool planToPosition(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res);
bool plan(motion_planning_msgs::KinematicPath &arm_path);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-07-01 20:19:58 UTC (rev 18122)
@@ -346,7 +346,7 @@
}
/** plan to joint space goal */
-bool SBPLArmPlannerNode::planToState(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+bool SBPLArmPlannerNode::planToState(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
motion_planning_msgs::KinematicPath arm_path;
@@ -406,7 +406,7 @@
}
/** plan to cartesian goal(s) */
-bool SBPLArmPlannerNode::planToPosition(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+bool SBPLArmPlannerNode::planToPosition(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
// for(unsigned int i=0; i < req.get_start_state_size(); i++)
// {
@@ -510,7 +510,7 @@
}
/** call back function */
-bool SBPLArmPlannerNode::planKinematicPath(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+bool SBPLArmPlannerNode::planKinematicPath(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
ROS_INFO("Callback called\n");
Modified: pkg/trunk/sandbox/chomp_motion_planner/include/chomp_motion_planner/chomp_planner_node.h
===================================================================
--- pkg/trunk/sandbox/chomp_motion_planner/include/chomp_motion_planner/chomp_planner_node.h 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/sandbox/chomp_motion_planner/include/chomp_motion_planner/chomp_planner_node.h 2009-07-01 20:19:58 UTC (rev 18122)
@@ -38,7 +38,7 @@
#define CHOMP_PLANNER_NODE_H_
#include <ros/ros.h>
-#include <motion_planning_srvs/KinematicPlan.h>
+#include <motion_planning_srvs/MotionPlan.h>
#include <chomp_motion_planner/chomp_robot_model.h>
namespace chomp
@@ -77,7 +77,7 @@
/**
* \brief Main entry point for motion planning (callback for the plan_kinematic_path service)
*/
- bool planKinematicPath(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res);
+ bool planKinematicPath(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res);
private:
ros::NodeHandle node_handle_; /**< ROS Node handle */
Modified: pkg/trunk/sandbox/chomp_motion_planner/src/chomp_planner_node.cpp
===================================================================
--- pkg/trunk/sandbox/chomp_motion_planner/src/chomp_planner_node.cpp 2009-07-01 20:13:15 UTC (rev 18121)
+++ pkg/trunk/sandbox/chomp_motion_planner/src/chomp_planner_node.cpp 2009-07-01 20:19:58 UTC (rev 18122)
@@ -83,7 +83,7 @@
return 0;
}
-bool ChompPlannerNode::planKinematicPath(motion_planning_srvs::KinematicPlan::Request &req, motion_planning_srvs::KinematicPlan::Response &res)
+bool ChompPlannerNode::planKinematicPath(motion_planning_srvs::MotionPlan::Request &req, motion_planning_srvs::MotionPlan::Response &res)
{
// get the planning group:
const ChompRobotModel::ChompPlanningGroup* group = chomp_robot_model_.getPlanningGroup(req.params.model_id);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|