|
From: <is...@us...> - 2009-08-02 23:05:16
|
Revision: 20451
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20451&view=rev
Author: isucan
Date: 2009-08-02 23:05:07 +0000 (Sun, 02 Aug 2009)
Log Message:
-----------
renamed service
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp
pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp
pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.cpp
pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.h
Added Paths:
-----------
pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertToJointConstraint.srv
Removed Paths:
-------------
pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv
Modified: pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-08-02 23:05:07 UTC (rev 20451)
@@ -163,19 +163,19 @@
goal.goal_constraints.pose_constraint[0].pose.pose.orientation.z = pz[5];
goal.goal_constraints.pose_constraint[0].pose.pose.orientation.w = pz[6];
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.x = 0.01;
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.y = 0.01;
- goal.goal_constraints.pose_constraint[0].position_tolerance_above.z = 0.015;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.x = 0.01;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.y = 0.01;
- goal.goal_constraints.pose_constraint[0].position_tolerance_below.z = 0.015;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.x = 0.001;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.y = 0.001;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_above.z = 0.002;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.x = 0.001;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.y = 0.001;
+ goal.goal_constraints.pose_constraint[0].position_tolerance_below.z = 0.002;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.x = 0.05;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.y = 0.05;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.z = 0.05;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.x = 0.05;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.y = 0.05;
- goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.z = 0.05;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.x = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.y = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_above.z = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.x = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.y = 0.005;
+ goal.goal_constraints.pose_constraint[0].orientation_tolerance_below.z = 0.005;
goal.goal_constraints.pose_constraint[0].orientation_importance = 0.01;
}
@@ -477,6 +477,7 @@
{
std::vector<double> params(response.solution.begin() + n, response.solution.begin() + n + u);
sp.setParamsJoint(params, names[i]);
+ std::cout << names[i] << " = " << params[0] << std::endl;
}
n += u;
}
Modified: pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp 2009-08-02 23:05:07 UTC (rev 20451)
@@ -42,8 +42,7 @@
#include <pr2_mechanism_controllers/TrajectoryCancel.h>
#include <manipulation_srvs/IKService.h>
-#include <manipulation_srvs/IKQuery.h>
-#include <motion_planning_msgs/ConvertPoseToJointConstraint.h>
+#include <motion_planning_msgs/ConvertToJointConstraint.h>
#include <visualization_msgs/Marker.h>
#include <cstdlib>
@@ -613,7 +612,7 @@
else
{
// if it is not, we try to fix it
- motion_planning_msgs::ConvertPoseToJointConstraint::Request c_req;
+ motion_planning_msgs::ConvertToJointConstraint::Request c_req;
c_req.params = req.params;
c_req.start_state = req.start_state;
c_req.constraints = req.goal_constraints;
@@ -641,8 +640,8 @@
}
}
- motion_planning_msgs::ConvertPoseToJointConstraint::Response c_res;
- ros::ServiceClient s_client = node_handle_.serviceClient<motion_planning_msgs::ConvertPoseToJointConstraint>(SEARCH_VALID_STATE_NAME);
+ motion_planning_msgs::ConvertToJointConstraint::Response c_res;
+ ros::ServiceClient s_client = node_handle_.serviceClient<motion_planning_msgs::ConvertToJointConstraint>(SEARCH_VALID_STATE_NAME);
if (s_client.call(c_req, c_res))
{
if (!c_res.joint_constraint.empty())
@@ -661,14 +660,14 @@
}
else
{
- motion_planning_msgs::ConvertPoseToJointConstraint::Request c_req;
+ motion_planning_msgs::ConvertToJointConstraint::Request c_req;
c_req.params = req.params;
c_req.start_state = req.start_state;
c_req.constraints = req.goal_constraints;
c_req.names = arm_joint_names_;
c_req.allowed_time = 1.0;
- motion_planning_msgs::ConvertPoseToJointConstraint::Response c_res;
- ros::ServiceClient s_client = node_handle_.serviceClient<motion_planning_msgs::ConvertPoseToJointConstraint>(SEARCH_VALID_STATE_NAME);
+ motion_planning_msgs::ConvertToJointConstraint::Response c_res;
+ ros::ServiceClient s_client = node_handle_.serviceClient<motion_planning_msgs::ConvertToJointConstraint>(SEARCH_VALID_STATE_NAME);
if (s_client.call(c_req, c_res))
{
if (!c_res.joint_constraint.empty())
Deleted: pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv 2009-08-02 23:05:07 UTC (rev 20451)
@@ -1,30 +0,0 @@
-# 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 joint names, in the same order as the values in the state
-string[] names
-
-# A list of states, each with the dimension of the requested model.
-# The dimension of the model may be different from the number of joints
-# (when there are joints that use more than one parameter)
-# Each state is to be used as a hint (initialization) for the search
-# if the valid state
-motion_planning_msgs/KinematicState[] states
-
-# The input constraints, to be converted to a set of joint constraints
-motion_planning_msgs/KinematicConstraints constraints
-
-# The maximum amount of time the search is to be run for
-float64 allowed_time
-
----
-
-# The set of joint constraints that correspond to the pose constraint
-motion_planning_msgs/JointConstraint[] joint_constraint
Copied: pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertToJointConstraint.srv (from rev 20427, pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv)
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertToJointConstraint.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertToJointConstraint.srv 2009-08-02 23:05:07 UTC (rev 20451)
@@ -0,0 +1,30 @@
+# 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 joint names, in the same order as the values in the state
+string[] names
+
+# A list of states, each with the dimension of the requested model.
+# The dimension of the model may be different from the number of joints
+# (when there are joints that use more than one parameter)
+# Each state is to be used as a hint (initialization) for the search
+# if the valid state
+motion_planning_msgs/KinematicState[] states
+
+# The input constraints, to be converted to a set of joint constraints
+motion_planning_msgs/KinematicConstraints constraints
+
+# The maximum amount of time the search is to be run for
+float64 allowed_time
+
+---
+
+# The set of joint constraints that correspond to the pose constraint
+motion_planning_msgs/JointConstraint[] joint_constraint
Property changes on: pkg/trunk/motion_planning/motion_planning_msgs/srv/ConvertToJointConstraint.srv
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/motion_planning/motion_planning_msgs/srv/ConvertPoseToJointConstraint.srv:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Modified: pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp 2009-08-02 23:05:07 UTC (rev 20451)
@@ -36,7 +36,6 @@
#include "ompl_planning/Model.h"
#include "request_handler/RequestHandler.h"
-#include <motion_planning_msgs/ConvertPoseToJointConstraint.h>
using namespace ompl_planning;
@@ -180,7 +179,7 @@
return st;
}
- bool findValidState(motion_planning_msgs::ConvertPoseToJointConstraint::Request &req, motion_planning_msgs::ConvertPoseToJointConstraint::Response &res)
+ bool findValidState(motion_planning_msgs::ConvertToJointConstraint::Request &req, motion_planning_msgs::ConvertToJointConstraint::Response &res)
{
ROS_INFO("Received request for searching a valid state");
bool st = false;
Modified: pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.cpp 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.cpp 2009-08-02 23:05:07 UTC (rev 20451)
@@ -40,7 +40,7 @@
#include <sstream>
#include <cstdlib>
-bool ompl_planning::RequestHandler::isRequestValid(ModelMap &models, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req)
+bool ompl_planning::RequestHandler::isRequestValid(ModelMap &models, motion_planning_msgs::ConvertToJointConstraint::Request &req)
{
ModelMap::const_iterator pos = models.find(req.params.model_id);
@@ -186,7 +186,7 @@
return true;
}
-void ompl_planning::RequestHandler::configure(const planning_models::StateParams *startState, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req, IKSetup *iksetup)
+void ompl_planning::RequestHandler::configure(const planning_models::StateParams *startState, motion_planning_msgs::ConvertToJointConstraint::Request &req, IKSetup *iksetup)
{
/* clear memory */
iksetup->si->clearGoal();
@@ -332,8 +332,8 @@
return result;
}
-bool ompl_planning::RequestHandler::findState(ModelMap &models, const planning_models::StateParams *start, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req,
- motion_planning_msgs::ConvertPoseToJointConstraint::Response &res)
+bool ompl_planning::RequestHandler::findState(ModelMap &models, const planning_models::StateParams *start, motion_planning_msgs::ConvertToJointConstraint::Request &req,
+ motion_planning_msgs::ConvertToJointConstraint::Response &res)
{
if (!isRequestValid(models, req))
return false;
Modified: pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.h 2009-08-02 22:57:21 UTC (rev 20450)
+++ pkg/trunk/motion_planning/ompl_planning/src/request_handler/RequestHandler.h 2009-08-02 23:05:07 UTC (rev 20451)
@@ -40,7 +40,7 @@
#include "ompl_planning/Model.h"
#include <ros/ros.h>
#include <motion_planning_msgs/GetMotionPlan.h>
-#include <motion_planning_msgs/ConvertPoseToJointConstraint.h>
+#include <motion_planning_msgs/ConvertToJointConstraint.h>
/** \brief Main namespace */
namespace ompl_planning
@@ -85,13 +85,13 @@
bool isRequestValid(ModelMap &models, motion_planning_msgs::GetMotionPlan::Request &req);
/** \brief Check if the request is valid */
- bool isRequestValid(ModelMap &models, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req);
+ bool isRequestValid(ModelMap &models, motion_planning_msgs::ConvertToJointConstraint::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_msgs::GetMotionPlan::Request &req, motion_planning_msgs::GetMotionPlan::Response &res);
/** \brief Find a state in the specified goal region. Return true if state was found */
- bool findState(ModelMap &models, const planning_models::StateParams *start, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req, motion_planning_msgs::ConvertPoseToJointConstraint::Response &res);
+ bool findState(ModelMap &models, const planning_models::StateParams *start, motion_planning_msgs::ConvertToJointConstraint::Request &req, motion_planning_msgs::ConvertToJointConstraint::Response &res);
private:
@@ -106,7 +106,7 @@
void configure(const planning_models::StateParams *startState, motion_planning_msgs::GetMotionPlan::Request &req, PlannerSetup *psetup);
/** \brief Set up all the data needed by inverse kinematics based on a request */
- void configure(const planning_models::StateParams *startState, motion_planning_msgs::ConvertPoseToJointConstraint::Request &req, IKSetup *iksetup);
+ void configure(const planning_models::StateParams *startState, motion_planning_msgs::ConvertToJointConstraint::Request &req, IKSetup *iksetup);
/** \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);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|