|
From: <is...@us...> - 2008-08-04 19:57:56
|
Revision: 2509
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2509&view=rev
Author: isucan
Date: 2008-08-04 19:57:51 +0000 (Mon, 04 Aug 2008)
Log Message:
-----------
updated messages for motion planning (not yet final)
Modified Paths:
--------------
pkg/trunk/messages/robot_msgs/msg/KinematicPath.msg
pkg/trunk/messages/robot_msgs/msg/KinematicState.msg
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv
Added Paths:
-----------
pkg/trunk/messages/robot_msgs/msg/KinematicConstraint.msg
Added: pkg/trunk/messages/robot_msgs/msg/KinematicConstraint.msg
===================================================================
--- pkg/trunk/messages/robot_msgs/msg/KinematicConstraint.msg (rev 0)
+++ pkg/trunk/messages/robot_msgs/msg/KinematicConstraint.msg 2008-08-04 19:57:51 UTC (rev 2509)
@@ -0,0 +1,22 @@
+# This message contains the definition of a motion planning constraint.
+# Since there are multiple types of constraints, the 'type' member is used
+# to identify the different constraints
+
+
+# Value that identifies the type of constraint
+byte type
+
+
+##########################################
+# For constraints of type 0 #
+# (position of center of a certain body) #
+##########################################
+
+# The name of the body (link) for which the constraint is defined
+string body
+
+# The position of the body
+std_msgs/Point3DFloat64 position
+
+# The tolerance for this position
+float64 tolerance
Modified: pkg/trunk/messages/robot_msgs/msg/KinematicPath.msg
===================================================================
--- pkg/trunk/messages/robot_msgs/msg/KinematicPath.msg 2008-08-04 19:50:39 UTC (rev 2508)
+++ pkg/trunk/messages/robot_msgs/msg/KinematicPath.msg 2008-08-04 19:57:51 UTC (rev 2509)
@@ -1 +1,3 @@
+# The definition of a kinematic path. Simply a list of states
+
KinematicState[] states
Modified: pkg/trunk/messages/robot_msgs/msg/KinematicState.msg
===================================================================
--- pkg/trunk/messages/robot_msgs/msg/KinematicState.msg 2008-08-04 19:50:39 UTC (rev 2508)
+++ pkg/trunk/messages/robot_msgs/msg/KinematicState.msg 2008-08-04 19:57:51 UTC (rev 2509)
@@ -1 +1,4 @@
+# The definition of a kinematic state. Simply a list of double
+# precision floating point values
+
float64[] vals
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-04 19:50:39 UTC (rev 2508)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-08-04 19:57:51 UTC (rev 2509)
@@ -268,7 +268,7 @@
goal->state = new ompl::SpaceInformationKinematic::StateKinematic(dim);
for (int i = 0 ; i < dim ; ++i)
goal->state->values[i] = req.goal_state.vals[i];
- goal->threshold = 1e-6;
+ goal->threshold = req.threshold;
p.si->setGoal(goal);
printf("=======================================\n");
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-04 19:50:39 UTC (rev 2508)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-08-04 19:57:51 UTC (rev 2509)
@@ -49,6 +49,8 @@
robot_srvs::KinematicMotionPlan::response res;
req.model_id = "pr2::base+arms";
+ req.threshold = 1e-6;
+ req.distance_metric = "L2Square";
req.start_state.set_vals_size(34);
for (unsigned int i = 0 ; i < req.start_state.vals_size ; ++i)
Modified: pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv
===================================================================
--- pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv 2008-08-04 19:50:39 UTC (rev 2508)
+++ pkg/trunk/services/robot_srvs/srv/KinematicMotionPlan.srv 2008-08-04 19:57:51 UTC (rev 2509)
@@ -1,8 +1,63 @@
+# 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 constraints the motion planner should respect
+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
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|