|
From: <is...@us...> - 2008-08-17 22:22:24
|
Revision: 3189
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3189&view=rev
Author: isucan
Date: 2008-08-17 22:22:33 +0000 (Sun, 17 Aug 2008)
Log Message:
-----------
renamed services for motion planning
Modified Paths:
--------------
pkg/trunk/motion_planning/issue_kinematic_plan/src/issue_kinematic_plan.cpp
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/robot_msgs/msg/KinematicConstraint.msg
Added Paths:
-----------
pkg/trunk/robot_srvs/srv/KinematicPlanLinkPosition.srv
pkg/trunk/robot_srvs/srv/KinematicPlanState.srv
Removed Paths:
-------------
pkg/trunk/robot_srvs/srv/KinematicMotionPlan.srv
Modified: pkg/trunk/motion_planning/issue_kinematic_plan/src/issue_kinematic_plan.cpp
===================================================================
--- pkg/trunk/motion_planning/issue_kinematic_plan/src/issue_kinematic_plan.cpp 2008-08-17 21:40:45 UTC (rev 3188)
+++ pkg/trunk/motion_planning/issue_kinematic_plan/src/issue_kinematic_plan.cpp 2008-08-17 22:22:33 UTC (rev 3189)
@@ -36,7 +36,7 @@
#include <std_msgs/PR2Arm.h>
#include <pr2_msgs/MoveArmGoal.h>
#include <pr2_msgs/MoveArmState.h>
-#include <robot_srvs/KinematicMotionPlan.h>
+#include <robot_srvs/KinematicPlanState.h>
static const double L1_JOINT_DIFF_MAX = .01;
static const double L1_GRIP_FORCE_DIFF_MAX = .01;
@@ -197,7 +197,7 @@
void moveLeftArm() {
- robot_srvs::KinematicMotionPlan::request req;
+ robot_srvs::KinematicPlanState::request req;
req.model_id = "pr2::leftArm";
req.threshold = 10e-06;
@@ -286,7 +286,7 @@
void moveRightArm() {
- robot_srvs::KinematicMotionPlan::request req;
+ robot_srvs::KinematicPlanState::request req;
req.model_id = "pr2::rightArm";
req.threshold = 10e-04;
@@ -385,7 +385,7 @@
private:
- void setStateGoalFromPlan(unsigned int state_num, const robot_srvs::KinematicMotionPlan::response& res,
+ void setStateGoalFromPlan(unsigned int state_num, const robot_srvs::KinematicPlanState::response& res,
std_msgs::PR2Arm& arm_com) {
if(state_num >= res.path.get_states_size()) {
printf("SetStateGoalFromPlan:: trying to set state greater than number of states in path.\n");
@@ -411,8 +411,8 @@
private:
- robot_srvs::KinematicMotionPlan::response left_plan_res_;
- robot_srvs::KinematicMotionPlan::response right_plan_res_;
+ robot_srvs::KinematicPlanState::response left_plan_res_;
+ robot_srvs::KinematicPlanState::response right_plan_res_;
std_msgs::PR2Arm left_arm_command_;
std_msgs::PR2Arm right_arm_command_;
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-17 21:40:45 UTC (rev 3188)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-17 22:22:33 UTC (rev 3189)
@@ -86,7 +86,8 @@
**/
#include <planning_node_util/cnode.h>
-#include <robot_srvs/KinematicMotionPlan.h>
+#include <robot_srvs/KinematicPlanState.h>
+#include <robot_srvs/KinematicPlanLinkPosition.h>
#include <ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h>
#include <ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h>
@@ -115,7 +116,7 @@
delete i->second;
}
- bool plan(robot_srvs::KinematicMotionPlan::request &req, robot_srvs::KinematicMotionPlan::response &res)
+ bool plan(robot_srvs::KinematicPlanState::request &req, robot_srvs::KinematicPlanState::response &res)
{
if (m_models.find(req.model_id) == m_models.end())
{
Modified: pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-08-17 21:40:45 UTC (rev 3188)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-08-17 22:22:33 UTC (rev 3189)
@@ -34,7 +34,7 @@
#include <ros/node.h>
#include <ros/time.h>
-#include <robot_srvs/KinematicMotionPlan.h>
+#include <robot_srvs/KinematicPlanState.h>
#include <robot_msgs/NamedKinematicPath.h>
#include <std_msgs/RobotBase2DOdom.h>
@@ -58,7 +58,7 @@
void runTestBase(void)
{
- robot_srvs::KinematicMotionPlan::request req;
+ robot_srvs::KinematicPlanState::request req;
req.model_id = "pr2::base";
req.threshold = 0.01;
@@ -87,7 +87,7 @@
void runTestLeftArm(void)
{
- robot_srvs::KinematicMotionPlan::request req;
+ robot_srvs::KinematicPlanState::request req;
req.model_id = "pr2::leftArm";
req.threshold = 0.01;
@@ -109,9 +109,9 @@
performCall(req);
}
- void performCall(robot_srvs::KinematicMotionPlan::request &req)
+ void performCall(robot_srvs::KinematicPlanState::request &req)
{
- robot_srvs::KinematicMotionPlan::response res;
+ robot_srvs::KinematicPlanState::response res;
robot_msgs::NamedKinematicPath dpath;
if (ros::service::call("plan_kinematic_path", req, res))
Modified: pkg/trunk/robot_msgs/msg/KinematicConstraint.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/KinematicConstraint.msg 2008-08-17 21:40:45 UTC (rev 3188)
+++ pkg/trunk/robot_msgs/msg/KinematicConstraint.msg 2008-08-17 22:22:33 UTC (rev 3189)
@@ -2,3 +2,19 @@
# Since there are multiple types of constraints, the 'type' member is used
# to identify the different constraints
+# 0 = complete pose is considered
+# 1 = only pose position is considered
+# 2 = only pose orientation is considered
+byte type
+
+# The robot link this constraint refers to
+string robot_link
+
+# The desired pose of the robot link
+std_msgs/Pose3DFloat64 pose
+
+# the allowed difference (euclidian distance) for position
+float64 position_distance
+
+# the allowed difference (shortest angular distance) for orientation
+float64 orientation_distance
Deleted: pkg/trunk/robot_srvs/srv/KinematicMotionPlan.srv
===================================================================
--- pkg/trunk/robot_srvs/srv/KinematicMotionPlan.srv 2008-08-17 21:40:45 UTC (rev 3188)
+++ pkg/trunk/robot_srvs/srv/KinematicMotionPlan.srv 2008-08-17 22:22:33 UTC (rev 3189)
@@ -1,64 +0,0 @@
-# This message contains the definition for a request to the motion
-# planner
-
-
-
-# The model (defined in pr2.xml as a group) for which the motion
-# planner should plan for
-string model_id
-
-
-# The starting state for the robot. This is eth complete state of the
-# robot, all joint values, everything that needs to be specified to
-# completely define where each part of the robot is in space. The
-# meaning for each element in the state vector can be extracted from
-# viewing the output of the robot model construction (the kinematic
-# model constructed from the parsed URDF model) in verbose mode
-robot_msgs/KinematicState start_state
-
-
-# The goal state for the model to plan for. The dimension of this
-# state must be equal to the dimension of the state space
-# characterizing the model (group) to plan for. If this state has
-# dimension 0, it is assumed that the first state that satisfies the
-# constraints is correct
-robot_msgs/KinematicState goal_state
-
-
-# The maximum amount of time the motion planner is allowed to plan for
-float64 allowed_time
-
-
-# A string that identifies which distance metric the planner should use
-string distance_metric
-
-
-# The threshold (distance) that is allowed between the returned
-# solution and the actual goal
-float64 threshold
-
-
-# Lower coordinate for a box defining the volume in the workspace the
-# motion planner is active in. If planning in 2D, only first 2 values
-# (x, y) of the points are used.
-std_msgs/Point3DFloat64 volumeMin
-
-
-# Higher coordinate for the box described above
-std_msgs/Point3DFloat64 volumeMax
-
----
-
-# The result of a motion plan: a kinematic path. If the motion plan is
-# not succesful, this path has 0 states. If the motion plan is
-# succesful, this path contains the minimum number of states (but it
-# includes start and goal states) to define the motions for the
-# robot. If more intermediate states are needed, linear interpolation
-# is to be assumed.
-robot_msgs/KinematicPath path
-
-
-# The threshold that was actually achieved. If the planner did not have enough time,
-# it may return a distance larger than the desired threshold. The user may choose to
-# discard the path
-float64 distance
Added: pkg/trunk/robot_srvs/srv/KinematicPlanLinkPosition.srv
===================================================================
--- pkg/trunk/robot_srvs/srv/KinematicPlanLinkPosition.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/KinematicPlanLinkPosition.srv 2008-08-17 22:22:33 UTC (rev 3189)
@@ -0,0 +1,60 @@
+# This message contains the definition for a request to the motion
+# planner
+
+
+
+# The model (defined in pr2.xml as a group) for which the motion
+# planner should plan for
+string model_id
+
+
+# The starting state for the robot. This is eth complete state of the
+# robot, all joint values, everything that needs to be specified to
+# completely define where each part of the robot is in space. The
+# meaning for each element in the state vector can be extracted from
+# viewing the output of the robot model construction (the kinematic
+# model constructed from the parsed URDF model) in verbose mode
+robot_msgs/KinematicState start_state
+
+
+# The goal state for the model to plan for. The state is not explicit.
+# The goal is considered achieved if all the constraints are satisfied.
+robot_msgs/KinematicConstraint[] goal_constraints
+
+
+# No state in the produced motion plan will violate these constraints
+robot_msgs/KinematicConstraint[] constraints
+
+
+# The maximum amount of time the motion planner is allowed to plan for
+float64 allowed_time
+
+
+# A string that identifies which distance metric the planner should use
+string distance_metric
+
+
+# Lower coordinate for a box defining the volume in the workspace the
+# motion planner is active in. If planning in 2D, only first 2 values
+# (x, y) of the points are used.
+std_msgs/Point3DFloat64 volumeMin
+
+
+# Higher coordinate for the box described above
+std_msgs/Point3DFloat64 volumeMax
+
+---
+
+# The result of a motion plan: a kinematic path. If the motion plan is
+# not succesful, this path has 0 states. If the motion plan is
+# succesful, this path contains the minimum number of states (but it
+# includes start and goal states) to define the motions for the
+# robot. If more intermediate states are needed, linear interpolation
+# is to be assumed.
+robot_msgs/KinematicPath path
+
+
+# The threshold that was actually achieved. If the planner did not have enough time,
+# it may return a distance larger than the desired threshold. The user may choose to
+# discard the path
+float64 distance
Copied: pkg/trunk/robot_srvs/srv/KinematicPlanState.srv (from rev 3185, pkg/trunk/robot_srvs/srv/KinematicMotionPlan.srv)
===================================================================
--- pkg/trunk/robot_srvs/srv/KinematicPlanState.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/KinematicPlanState.srv 2008-08-17 22:22:33 UTC (rev 3189)
@@ -0,0 +1,67 @@
+# This message contains the definition for a request to the motion
+# planner
+
+
+
+# The model (defined in pr2.xml as a group) for which the motion
+# planner should plan for
+string model_id
+
+
+# The starting state for the robot. This is eth complete state of the
+# robot, all joint values, everything that needs to be specified to
+# completely define where each part of the robot is in space. The
+# meaning for each element in the state vector can be extracted from
+# viewing the output of the robot model construction (the kinematic
+# model constructed from the parsed URDF model) in verbose mode
+robot_msgs/KinematicState start_state
+
+
+# The goal state for the model to plan for. The dimension of this
+# state must be equal to the dimension of the state space
+# characterizing the model (group) to plan for. If this state has
+# dimension 0, it is assumed that the first state that satisfies the
+# constraints is correct
+robot_msgs/KinematicState goal_state
+
+
+# No state in the produced motion plan will violate these constraints
+robot_msgs/KinematicConstraint[] constraints
+
+# The maximum amount of time the motion planner is allowed to plan for
+float64 allowed_time
+
+
+# A string that identifies which distance metric the planner should use
+string distance_metric
+
+
+# The threshold (distance) that is allowed between the returned
+# solution and the actual goal
+float64 threshold
+
+
+# Lower coordinate for a box defining the volume in the workspace the
+# motion planner is active in. If planning in 2D, only first 2 values
+# (x, y) of the points are used.
+std_msgs/Point3DFloat64 volumeMin
+
+
+# Higher coordinate for the box described above
+std_msgs/Point3DFloat64 volumeMax
+
+---
+
+# The result of a motion plan: a kinematic path. If the motion plan is
+# not succesful, this path has 0 states. If the motion plan is
+# succesful, this path contains the minimum number of states (but it
+# includes start and goal states) to define the motions for the
+# robot. If more intermediate states are needed, linear interpolation
+# is to be assumed.
+robot_msgs/KinematicPath path
+
+
+# The threshold that was actually achieved. If the planner did not have enough time,
+# it may return a distance larger than the desired threshold. The user may choose to
+# discard the path
+float64 distance
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|