|
From: <is...@us...> - 2009-01-23 22:54:28
|
Revision: 10089
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10089&view=rev
Author: isucan
Date: 2009-01-23 22:54:25 +0000 (Fri, 23 Jan 2009)
Log Message:
-----------
more flexibility in specifying constraints
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPConstraintEvaluator.h
pkg/trunk/prcore/robot_msgs/msg/PoseConstraint.msg
Modified: pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-01-23 22:48:37 UTC (rev 10088)
+++ pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-01-23 22:54:25 UTC (rev 10089)
@@ -104,7 +104,7 @@
m_pce[i]->evaluate(&dPos, &dAng);
if (decision)
(*decision)[i] = m_pce[i]->decide(dPos, dAng);
- distance += dPos + dAng;
+ distance += dPos + m_pce[i]->getConstraintMessage().orientation_importance * dAng;
}
return distance;
Modified: pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPConstraintEvaluator.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPConstraintEvaluator.h 2009-01-23 22:48:37 UTC (rev 10088)
+++ pkg/trunk/motion_planning/kinematic_planning/include/kinematic_planning/RKPConstraintEvaluator.h 2009-01-23 22:54:25 UTC (rev 10089)
@@ -165,6 +165,11 @@
return result;
}
+ const robot_msgs::PoseConstraint& getConstraintMessage(void) const
+ {
+ return m_pc;
+ }
+
virtual void print(std::ostream &out = std::cout) const
{
if (m_link)
Modified: pkg/trunk/prcore/robot_msgs/msg/PoseConstraint.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/PoseConstraint.msg 2009-01-23 22:48:37 UTC (rev 10088)
+++ pkg/trunk/prcore/robot_msgs/msg/PoseConstraint.msg 2009-01-23 22:54:25 UTC (rev 10089)
@@ -12,10 +12,15 @@
string robot_link
# The desired pose of the robot link
-std_msgs/Pose3D pose
+std_msgs/Pose pose
# the allowed difference (square of euclidian distance) for position
float64 position_distance
# the allowed difference (shortest angular distance) for orientation
float64 orientation_distance
+
+# a factor that gets multiplied to the orientation when computing the
+# distance to the goal.
+# Distance_to_goal = position_distance + orientation_importance * orientation_distance
+float64 orientation_importance
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|