|
From: <is...@us...> - 2009-05-11 21:23:18
|
Revision: 15190
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=15190&view=rev
Author: isucan
Date: 2009-05-11 21:22:55 +0000 (Mon, 11 May 2009)
Log Message:
-----------
moved my planning messages and services to motion_planning_[msgs/srvs]
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/CollisionSpaceMonitor.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequest.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestState.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPConstraintEvaluator.h
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/ompl_extensions/RKPStateValidator.h
pkg/trunk/motion_planning/ompl_planning/manifest.xml
pkg/trunk/motion_planning/ompl_planning/src/motion_planner.cpp
pkg/trunk/motion_planning/ompl_planning/src/motion_validator.cpp
pkg/trunk/motion_planning/ompl_planning/test/avoid_monster.cpp
pkg/trunk/motion_planning/plan_ompl_path/manifest.xml
pkg/trunk/motion_planning/plan_ompl_path/src/base/execute_plan_to_state_minimal.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/plan_kinematic_path.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_plan_to_position_minimal.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_plan_to_state.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_plan_to_state_minimal.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_replan_to_state.cpp
pkg/trunk/pr2_msgs/manifest.xml
pkg/trunk/pr2_msgs/msg/MoveArmGoal.msg
pkg/trunk/visualization/rviz/manifest.xml
pkg/trunk/visualization/rviz/src/rviz/displays/planning_display.cpp
pkg/trunk/visualization/rviz/src/rviz/displays/planning_display.h
Added Paths:
-----------
pkg/trunk/motion_planning/motion_planning_msgs/
pkg/trunk/motion_planning/motion_planning_msgs/CMakeLists.txt
pkg/trunk/motion_planning/motion_planning_msgs/Makefile
pkg/trunk/motion_planning/motion_planning_msgs/manifest.xml
pkg/trunk/motion_planning/motion_planning_msgs/msg/
pkg/trunk/motion_planning/motion_planning_msgs/msg/DisplayKinematicPath.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicConstraints.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPath.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanLinkPositionRequest.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStateRequest.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStatus.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicSpaceParameters.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicState.msg
pkg/trunk/motion_planning/motion_planning_msgs/msg/PoseConstraint.msg
pkg/trunk/motion_planning/motion_planning_srvs/
pkg/trunk/motion_planning/motion_planning_srvs/CMakeLists.txt
pkg/trunk/motion_planning/motion_planning_srvs/Makefile
pkg/trunk/motion_planning/motion_planning_srvs/mainpage.dox
pkg/trunk/motion_planning/motion_planning_srvs/manifest.xml
pkg/trunk/motion_planning/motion_planning_srvs/srv/
pkg/trunk/motion_planning/motion_planning_srvs/srv/CollisionCheckState.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanLinkPosition.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanState.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanLinkPosition.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanState.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicPath.srv
pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicState.srv
Removed Paths:
-------------
pkg/trunk/common/robot_msgs/msg/DisplayKinematicPath.msg
pkg/trunk/common/robot_msgs/msg/KinematicConstraints.msg
pkg/trunk/common/robot_msgs/msg/KinematicPath.msg
pkg/trunk/common/robot_msgs/msg/KinematicPlanLinkPositionRequest.msg
pkg/trunk/common/robot_msgs/msg/KinematicPlanStateRequest.msg
pkg/trunk/common/robot_msgs/msg/KinematicPlanStatus.msg
pkg/trunk/common/robot_msgs/msg/KinematicSpaceParameters.msg
pkg/trunk/common/robot_msgs/msg/KinematicState.msg
pkg/trunk/common/robot_msgs/msg/NamedKinematicPath.msg
pkg/trunk/common/robot_msgs/msg/NamedKinematicState.msg
pkg/trunk/common/robot_msgs/msg/PoseConstraint.msg
pkg/trunk/common/robot_srvs/srv/CollisionCheckState.srv
pkg/trunk/common/robot_srvs/srv/KinematicPlanLinkPosition.srv
pkg/trunk/common/robot_srvs/srv/KinematicPlanState.srv
pkg/trunk/common/robot_srvs/srv/KinematicReplanLinkPosition.srv
pkg/trunk/common/robot_srvs/srv/KinematicReplanState.srv
pkg/trunk/common/robot_srvs/srv/NamedKinematicPlanState.srv
pkg/trunk/common/robot_srvs/srv/ValidateKinematicPath.srv
pkg/trunk/common/robot_srvs/srv/ValidateKinematicState.srv
Deleted: pkg/trunk/common/robot_msgs/msg/DisplayKinematicPath.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/DisplayKinematicPath.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/DisplayKinematicPath.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,6 +0,0 @@
-# The definition of a kinematic path that has a name
-# The name identifies the part of the robot the path is for
-string frame_id
-string model_name
-KinematicState start_state
-KinematicPath path
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicConstraints.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicConstraints.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicConstraints.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,3 +0,0 @@
-# This message contains a list of motion planning constraints.
-
-PoseConstraint[] pose
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicPath.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicPath.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicPath.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,3 +0,0 @@
-# The definition of a kinematic path. Simply a list of states
-
-KinematicState[] states
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicPlanLinkPositionRequest.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicPlanLinkPositionRequest.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicPlanLinkPositionRequest.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,36 +0,0 @@
-# This message contains the definition for a request to the motion
-# planner
-
-
-# Parameters for the state space
-robot_msgs/KinematicSpaceParameters params
-
-
-# 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/PoseConstraint[] goal_constraints
-
-
-# No state in the produced motion plan will violate these constraints
-robot_msgs/KinematicConstraints constraints
-
-
-# The number of times this plan is to be computed. Shortest solution
-# will be reported.
-int32 times
-
-# Boolean flag: if true, the returned path will contain interpolated
-# states as well
-byte interpolate
-
-# The maximum amount of time the motion planner is allowed to plan for
-float64 allowed_time
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicPlanStateRequest.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicPlanStateRequest.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicPlanStateRequest.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,38 +0,0 @@
-# This message contains the definition for a request to the motion
-# planner
-
-# Parameters for the state space
-robot_msgs/KinematicSpaceParameters params
-
-# The starting state for the robot. This is the 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.
-robot_msgs/KinematicState goal_state
-
-# No state in the produced motion plan will violate these constraints
-robot_msgs/KinematicConstraints constraints
-
-# The number of times this plan is to be computed. Shortest solution
-# will be reported.
-int32 times
-
-# Boolean flag: if true, the returned path will contain interpolated
-# states as well
-byte interpolate
-
-# The maximum amount of time the motion planner is allowed to plan for
-float64 allowed_time
-
-
-# The threshold (distance) that is allowed between the returned
-# solution and the actual goal
-float64 threshold
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicPlanStatus.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicPlanStatus.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicPlanStatus.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,39 +0,0 @@
-# This message contains the definition for the state of a motion plan
-
-# The ID of the request the status message refers to. A value of -1 means that
-# replanning is not active
-int32 id
-
-# If the ID just changed, this value will be 1. Subsequent messages
-# will have the value equal to 0
-byte new_id
-
-# 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
-
-# If the starting state was already in the goal region,
-# this is set to 1. Otherwise, it will be set to 0
-byte done
-
-
-# If computing the path was not possible, this will be set to 0
-# otherwise, it will be 1
-byte valid
-
-# If the solution only gets close to the goal but does not reach it
-# this is set to 1. Otherwise, it will be set to 0
-byte approximate
-
-# If the data the planner has when planning is stale, set this flag to 1
-byte unsafe
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicSpaceParameters.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicSpaceParameters.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicSpaceParameters.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,24 +0,0 @@
-# This message contains a set of parameters useful in setting up a
-# kinematic space for planning
-
-# The model (defined in the robot description as a group of links)
-# for which the motion planner should plan for
-string model_id
-
-
-# The name of the motion planner to use. If no name is specified,
-# a default motion planner will be used
-string planner_id
-
-
-# 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.
-robot_msgs/Point volumeMin
-
-
-# Higher coordinate for the box described above
-robot_msgs/Point volumeMax
Deleted: pkg/trunk/common/robot_msgs/msg/KinematicState.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/KinematicState.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/KinematicState.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,4 +0,0 @@
-# The definition of a kinematic state. Simply a list of double
-# precision floating point values
-
-float64[] vals
Deleted: pkg/trunk/common/robot_msgs/msg/NamedKinematicPath.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/NamedKinematicPath.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/NamedKinematicPath.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,3 +0,0 @@
-# The definition of a kinematic path. Simply a list of states
-
-NamedKinematicState[] states
Deleted: pkg/trunk/common/robot_msgs/msg/NamedKinematicState.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/NamedKinematicState.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/NamedKinematicState.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,10 +0,0 @@
-#Provides a set of named states for joints. Each kinematic state is a joint,
-# and each of its vals is one of its axes.
-
-string[] names
-
-KinematicState[] joints
-
-
-
-
Deleted: pkg/trunk/common/robot_msgs/msg/PoseConstraint.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/PoseConstraint.msg 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_msgs/msg/PoseConstraint.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,49 +0,0 @@
-# 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
-
-
-int32 POSITION_XYZ=1 # only x,y,z of position is considered
-int32 POSITION_XY=2 # only x,y of position is considered
-int32 POSITION_XZ=3 # only x,z of position is considered
-int32 POSITION_YZ=4 # only y,z of position is considered
-int32 POSITION_X=5 # only x of position is considered
-int32 POSITION_Y=6 # only y of position is considered
-int32 POSITION_Z=7 # only z of position is considered
-
-# the next values can be combined with one of the above, so they are offset by
-# 256, so we can use bit operations on them
-
-int32 ORIENTATION_RPY=256 # only roll, pitch, yaw of orientation is considered
-int32 ORIENTATION_RY=512 # only roll, yaw of orientation is considered
-int32 ORIENTATION_RP=768 # only roll, yaw of orientation is considered
-int32 ORIENTATION_PY=1024 # only roll, yaw of orientation is considered
-int32 ORIENTATION_R=1280 # only roll, yaw of orientation is considered
-int32 ORIENTATION_P=1536 # only roll, yaw of orientation is considered
-int32 ORIENTATION_Y=1792 # only roll, yaw of orientation is considered
-
-int32 type
-
-# The robot link this constraint refers to
-string robot_link
-
-# The desired pose of the robot link (in the robot frame)
-float64 x
-float64 y
-float64 z
-
-# euler angles around YXZ
-float64 roll # around Z axis
-float64 pitch # around X axis
-float64 yaw # around Y axis
-
-# the allowed difference (square of euclidian distance) for position
-float64 position_distance
-
-# the allowed difference (shortest angular distance, in radians) 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
Deleted: pkg/trunk/common/robot_srvs/srv/CollisionCheckState.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/CollisionCheckState.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/CollisionCheckState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,18 +0,0 @@
-# This service is used to enable / disable the collision checking for
-# various links. The returned value is the old state of the collision
-# checking
-
-# The robot which contains the link
-string robot_name
-
-# The link name
-string link_name
-
-# The new state for collision checking on this link
-byte value
-
----
-
-# If succesful, the old state of collision checking (0 or 1)
-# If not succesful, -1
-byte value
Deleted: pkg/trunk/common/robot_srvs/srv/KinematicPlanLinkPosition.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/KinematicPlanLinkPosition.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/KinematicPlanLinkPosition.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,5 +0,0 @@
-robot_msgs/KinematicPlanLinkPositionRequest value
-
----
-
-robot_msgs/KinematicPlanStatus value
Deleted: pkg/trunk/common/robot_srvs/srv/KinematicPlanState.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/KinematicPlanState.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/KinematicPlanState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,5 +0,0 @@
-robot_msgs/KinematicPlanStateRequest value
-
----
-
-robot_msgs/KinematicPlanStatus value
Deleted: pkg/trunk/common/robot_srvs/srv/KinematicReplanLinkPosition.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/KinematicReplanLinkPosition.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/KinematicReplanLinkPosition.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,5 +0,0 @@
-robot_msgs/KinematicPlanLinkPositionRequest value
-
----
-
-int32 id
Deleted: pkg/trunk/common/robot_srvs/srv/KinematicReplanState.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/KinematicReplanState.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/KinematicReplanState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,5 +0,0 @@
-robot_msgs/KinematicPlanStateRequest value
-
----
-
-int32 id
Deleted: pkg/trunk/common/robot_srvs/srv/NamedKinematicPlanState.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/NamedKinematicPlanState.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/NamedKinematicPlanState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,54 +0,0 @@
-# This message contains the definition for a request to the motion
-# planner
-
-# Parameters for the state space
-robot_msgs/KinematicSpaceParameters params
-
-# 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/NamedKinematicState 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.
-robot_msgs/NamedKinematicState goal_state
-
-# No state in the produced motion plan will violate these constraints
-robot_msgs/KinematicConstraints constraints
-
-# The number of times this plan is to be computed. Shortest solution
-# will be reported.
-int32 times
-
-# Boolean flag: if true, the returned path will contain interpolated
-# states as well
-byte interpolate
-
-# The maximum amount of time the motion planner is allowed to plan for
-float64 allowed_time
-
-
-# The threshold (distance) that is allowed between the returned
-# solution and the actual goal
-float64 threshold
-
----
-
-# 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/NamedKinematicPath 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
Deleted: pkg/trunk/common/robot_srvs/srv/ValidateKinematicPath.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/ValidateKinematicPath.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/ValidateKinematicPath.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,27 +0,0 @@
-# This message contains the definition for a request to the state
-# validator
-
-# The model to validate for
-string model_id
-
-# The starting state for the robot. This is the 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 validate for. The dimension of this
-# state must be equal to the dimension of the state space
-# characterizing the model (group) to plan for.
-robot_msgs/KinematicState goal_state
-
-# No state in the produced motion plan will violate these constraints
-robot_msgs/KinematicConstraints constraints
-
----
-
-# Return true or false, to say if path is valid or not.
-byte valid
Deleted: pkg/trunk/common/robot_srvs/srv/ValidateKinematicState.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/ValidateKinematicState.srv 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/common/robot_srvs/srv/ValidateKinematicState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -1,26 +0,0 @@
-# This message contains the definition for a request to the state
-# validator
-
-# The model to validate for
-string model_id
-
-# The starting state for the robot. This is either the 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, or the state of the model. If only the state for the model is
-# specified, the rest of the values are taken from the robot's current
-# state.
-# 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 state
-
-
-# No state in the produced motion plan will violate these constraints
-robot_msgs/KinematicConstraints constraints
-
----
-
-# Return true or false, to say if state is valid or not.
-byte valid
Added: pkg/trunk/motion_planning/motion_planning_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/CMakeLists.txt 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+rospack(motion_planning_msgs)
+genmsg()
Added: pkg/trunk/motion_planning/motion_planning_msgs/Makefile
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/Makefile (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/Makefile 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/motion_planning/motion_planning_msgs/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/manifest.xml (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/manifest.xml 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,21 @@
+<package>
+ <description brief="motion_planning_msgs">
+
+ motion_planning_msgs
+
+ </description>
+ <author>Ioan Sucan/is...@wi...</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/motion_planning_msgs</url>
+
+ <depend package="std_msgs"/>
+ <depend package="robot_msgs"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp"/>
+ </export>
+
+</package>
+
+
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/DisplayKinematicPath.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/DisplayKinematicPath.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/DisplayKinematicPath.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,6 @@
+# The definition of a kinematic path that has a name
+# The name identifies the part of the robot the path is for
+string frame_id
+string model_name
+KinematicState start_state
+KinematicPath path
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicConstraints.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicConstraints.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicConstraints.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,3 @@
+# This message contains a list of motion planning constraints.
+
+PoseConstraint[] pose
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPath.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPath.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPath.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,3 @@
+# The definition of a kinematic path. Simply a list of states
+
+KinematicState[] states
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanLinkPositionRequest.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanLinkPositionRequest.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanLinkPositionRequest.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,36 @@
+# This message contains the definition for a request to the motion
+# planner
+
+
+# Parameters for the state space
+KinematicSpaceParameters params
+
+
+# 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
+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.
+PoseConstraint[] goal_constraints
+
+
+# No state in the produced motion plan will violate these constraints
+KinematicConstraints constraints
+
+
+# The number of times this plan is to be computed. Shortest solution
+# will be reported.
+int32 times
+
+# Boolean flag: if true, the returned path will contain interpolated
+# states as well
+byte interpolate
+
+# The maximum amount of time the motion planner is allowed to plan for
+float64 allowed_time
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStateRequest.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStateRequest.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStateRequest.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,38 @@
+# This message contains the definition for a request to the motion
+# planner
+
+# Parameters for the state space
+KinematicSpaceParameters params
+
+# The starting state for the robot. This is the 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
+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.
+KinematicState goal_state
+
+# No state in the produced motion plan will violate these constraints
+KinematicConstraints constraints
+
+# The number of times this plan is to be computed. Shortest solution
+# will be reported.
+int32 times
+
+# Boolean flag: if true, the returned path will contain interpolated
+# states as well
+byte interpolate
+
+# The maximum amount of time the motion planner is allowed to plan for
+float64 allowed_time
+
+
+# The threshold (distance) that is allowed between the returned
+# solution and the actual goal
+float64 threshold
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStatus.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStatus.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicPlanStatus.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,39 @@
+# This message contains the definition for the state of a motion plan
+
+# The ID of the request the status message refers to. A value of -1 means that
+# replanning is not active
+int32 id
+
+# If the ID just changed, this value will be 1. Subsequent messages
+# will have the value equal to 0
+byte new_id
+
+# 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.
+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
+
+# If the starting state was already in the goal region,
+# this is set to 1. Otherwise, it will be set to 0
+byte done
+
+
+# If computing the path was not possible, this will be set to 0
+# otherwise, it will be 1
+byte valid
+
+# If the solution only gets close to the goal but does not reach it
+# this is set to 1. Otherwise, it will be set to 0
+byte approximate
+
+# If the data the planner has when planning is stale, set this flag to 1
+byte unsafe
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicSpaceParameters.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicSpaceParameters.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicSpaceParameters.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,24 @@
+# This message contains a set of parameters useful in setting up a
+# kinematic space for planning
+
+# The model (defined in the robot description as a group of links)
+# for which the motion planner should plan for
+string model_id
+
+
+# The name of the motion planner to use. If no name is specified,
+# a default motion planner will be used
+string planner_id
+
+
+# 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.
+robot_msgs/Point volumeMin
+
+
+# Higher coordinate for the box described above
+robot_msgs/Point volumeMax
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicState.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicState.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/KinematicState.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,4 @@
+# The definition of a kinematic state. Simply a list of double
+# precision floating point values
+
+float64[] vals
Added: pkg/trunk/motion_planning/motion_planning_msgs/msg/PoseConstraint.msg
===================================================================
--- pkg/trunk/motion_planning/motion_planning_msgs/msg/PoseConstraint.msg (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_msgs/msg/PoseConstraint.msg 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,49 @@
+# 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
+
+
+int32 POSITION_XYZ=1 # only x,y,z of position is considered
+int32 POSITION_XY=2 # only x,y of position is considered
+int32 POSITION_XZ=3 # only x,z of position is considered
+int32 POSITION_YZ=4 # only y,z of position is considered
+int32 POSITION_X=5 # only x of position is considered
+int32 POSITION_Y=6 # only y of position is considered
+int32 POSITION_Z=7 # only z of position is considered
+
+# the next values can be combined with one of the above, so they are offset by
+# 256, so we can use bit operations on them
+
+int32 ORIENTATION_RPY=256 # only roll, pitch, yaw of orientation is considered
+int32 ORIENTATION_RY=512 # only roll, yaw of orientation is considered
+int32 ORIENTATION_RP=768 # only roll, yaw of orientation is considered
+int32 ORIENTATION_PY=1024 # only roll, yaw of orientation is considered
+int32 ORIENTATION_R=1280 # only roll, yaw of orientation is considered
+int32 ORIENTATION_P=1536 # only roll, yaw of orientation is considered
+int32 ORIENTATION_Y=1792 # only roll, yaw of orientation is considered
+
+int32 type
+
+# The robot link this constraint refers to
+string robot_link
+
+# The desired pose of the robot link (in the robot frame)
+float64 x
+float64 y
+float64 z
+
+# euler angles around YXZ
+float64 roll # around Z axis
+float64 pitch # around X axis
+float64 yaw # around Y axis
+
+# the allowed difference (square of euclidian distance) for position
+float64 position_distance
+
+# the allowed difference (shortest angular distance, in radians) 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
Added: pkg/trunk/motion_planning/motion_planning_srvs/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/CMakeLists.txt (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/CMakeLists.txt 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+rospack(motion_planning_srvs)
+gensrv()
Added: pkg/trunk/motion_planning/motion_planning_srvs/Makefile
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/Makefile (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/Makefile 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/motion_planning/motion_planning_srvs/mainpage.dox
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/mainpage.dox (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/mainpage.dox 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,107 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b motion_planning/motion_planning_srvs is ... In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+
+
+\section codeapi Code API
+
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group
+so that it can be viewed separately. The rospy documentation
+similarly has a 'client-api' group that pulls together APIs for a
+Client API page.
+
+
+\section rosapi ROS API
+
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+
+<!-- START: copy for each node -->
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+<!-- END: copy for each node -->
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+*/
\ No newline at end of file
Added: pkg/trunk/motion_planning/motion_planning_srvs/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/manifest.xml (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/manifest.xml 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,22 @@
+<package>
+ <description brief="motion_planning/motion_planning_srvs">
+
+ motion_planning/motion_planning_srvs
+
+ </description>
+ <author>Ioan Sucan/is...@wi...</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/motion_planning/motion_planning_srvs</url>
+
+ <depend package="std_msgs"/>
+ <depend package="robot_msgs"/>
+ <depend package="motion_planning_msgs"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/srv/cpp"/>
+ </export>
+
+</package>
+
+
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/CollisionCheckState.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/CollisionCheckState.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/CollisionCheckState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,18 @@
+# This service is used to enable / disable the collision checking for
+# various links. The returned value is the old state of the collision
+# checking
+
+# The robot which contains the link
+string robot_name
+
+# The link name
+string link_name
+
+# The new state for collision checking on this link
+byte value
+
+---
+
+# If succesful, the old state of collision checking (0 or 1)
+# If not succesful, -1
+byte value
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanLinkPosition.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanLinkPosition.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanLinkPosition.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,5 @@
+motion_planning_msgs/KinematicPlanLinkPositionRequest value
+
+---
+
+motion_planning_msgs/KinematicPlanStatus value
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanState.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanState.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicPlanState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,5 @@
+motion_planning_msgs/KinematicPlanStateRequest value
+
+---
+
+motion_planning_msgs/KinematicPlanStatus value
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanLinkPosition.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanLinkPosition.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanLinkPosition.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,5 @@
+motion_planning_msgs/KinematicPlanLinkPositionRequest value
+
+---
+
+int32 id
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanState.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanState.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/KinematicReplanState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,5 @@
+motion_planning_msgs/KinematicPlanStateRequest value
+
+---
+
+int32 id
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicPath.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicPath.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicPath.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,27 @@
+# This message contains the definition for a request to the state
+# validator
+
+# The model to validate for
+string model_id
+
+# The starting state for the robot. This is the 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
+motion_planning_msgs/KinematicState start_state
+
+
+# The goal state for the model to validate for. The dimension of this
+# state must be equal to the dimension of the state space
+# characterizing the model (group) to plan for.
+motion_planning_msgs/KinematicState goal_state
+
+# No state in the produced motion plan will violate these constraints
+motion_planning_msgs/KinematicConstraints constraints
+
+---
+
+# Return true or false, to say if path is valid or not.
+byte valid
Added: pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicState.srv
===================================================================
--- pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicState.srv (rev 0)
+++ pkg/trunk/motion_planning/motion_planning_srvs/srv/ValidateKinematicState.srv 2009-05-11 21:22:55 UTC (rev 15190)
@@ -0,0 +1,26 @@
+# This message contains the definition for a request to the state
+# validator
+
+# The model to validate for
+string model_id
+
+# The starting state for the robot. This is either the 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, or the state of the model. If only the state for the model is
+# specified, the rest of the values are taken from the robot's current
+# state.
+# 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
+motion_planning_msgs/KinematicState state
+
+
+# No state in the produced motion plan will violate these constraints
+motion_planning_msgs/KinematicConstraints constraints
+
+---
+
+# Return true or false, to say if state is valid or not.
+byte valid
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/CollisionSpaceMonitor.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/CollisionSpaceMonitor.h 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/CollisionSpaceMonitor.h 2009-05-11 21:22:55 UTC (rev 15190)
@@ -40,7 +40,7 @@
#include <robot_msgs/PointCloud.h>
#include <robot_msgs/CollisionMap.h>
#include <robot_msgs/AttachedObject.h>
-#include <robot_srvs/CollisionCheckState.h>
+#include <motion_planning_srvs/CollisionCheckState.h>
/** Main namespace */
namespace kinematic_planning
@@ -169,7 +169,7 @@
afterAttachBody(link);
}
- bool setCollisionState(robot_srvs::CollisionCheckState::Request &req, robot_srvs::CollisionCheckState::Response &res)
+ bool setCollisionState(motion_planning_srvs::CollisionCheckState::Request &req, motion_planning_srvs::CollisionCheckState::Response &res)
{
m_collisionSpace->lock();
int model_id = m_collisionSpace->getModelID(req.robot_name);
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequest.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequest.h 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequest.h 2009-05-11 21:22:55 UTC (rev 15190)
@@ -39,9 +39,9 @@
#include "kinematic_planning/RKPModel.h"
-#include <robot_msgs/KinematicPath.h>
-#include <robot_msgs/KinematicSpaceParameters.h>
-#include <robot_msgs/PoseConstraint.h>
+#include <motion_planning_msgs/KinematicPath.h>
+#include <motion_planning_msgs/KinematicSpaceParameters.h>
+#include <motion_planning_msgs/PoseConstraint.h>
#include <ros/console.h>
#include <iostream>
@@ -139,7 +139,7 @@
return m_activeReq;
}
- bool isStillValid(robot_msgs::KinematicPath &path)
+ bool isStillValid(motion_planning_msgs::KinematicPath &path)
{
update();
@@ -180,7 +180,7 @@
return trivial;
}
- void execute(robot_msgs::KinematicPath &path, double &distance, bool &trivial, bool &approximate)
+ void execute(motion_planning_msgs::KinematicPath &path, double &distance, bool &trivial, bool &approximate)
{
update();
@@ -218,7 +218,7 @@
/* configure state space and starting state */
setupStateSpaceAndStartState(m_activePSetup, m_activeReq.params, m_activeReq.start_state);
- std::vector<robot_msgs::PoseConstraint> cstrs;
+ std::vector<motion_planning_msgs::PoseConstraint> cstrs;
m_activeReq.constraints.get_pose_vec(cstrs);
setupPoseConstraints(m_activePSetup, cstrs);
@@ -227,7 +227,7 @@
}
/** Validate common space parameters */
- bool areSpaceParamsValid(const ModelMap &modelsRef, robot_msgs::KinematicSpaceParameters ¶ms) const
+ bool areSpaceParamsValid(const ModelMap &modelsRef, motion_planning_msgs::KinematicSpaceParameters ¶ms) const
{
ModelMap::const_iterator pos = modelsRef.find(params.model_id);
@@ -269,8 +269,8 @@
/** Configure the state space for a given set of parameters and set the starting state */
void setupStateSpaceAndStartState(RKPPlannerSetup *psetup,
- robot_msgs::KinematicSpaceParameters ¶ms,
- robot_msgs::KinematicState &start_state)
+ motion_planning_msgs::KinematicSpaceParameters ¶ms,
+ motion_planning_msgs::KinematicState &start_state)
{
/* set the workspace volume for planning */
// only area or volume should go through... not sure what happens on really complicated models where
@@ -307,7 +307,7 @@
}
/** Set the kinematic constraints to follow */
- void setupPoseConstraints(RKPPlannerSetup *psetup, const std::vector<robot_msgs::PoseConstraint> &cstrs)
+ void setupPoseConstraints(RKPPlannerSetup *psetup, const std::vector<motion_planning_msgs::PoseConstraint> &cstrs)
{
static_cast<StateValidityPredicate*>(psetup->si->getStateValidityChecker())->setPoseConstraints(cstrs);
}
@@ -395,7 +395,7 @@
}
void fillSolution(RKPPlannerSetup *psetup, ompl::sb::PathKinematic *bestPath, double bestDifference,
- robot_msgs::KinematicPath &path, double &distance)
+ motion_planning_msgs::KinematicPath &path, double &distance)
{
const unsigned int dim = psetup->si->getStateDimension();
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestLinkPosition.h 2009-05-11 21:22:55 UTC (rev 15190)
@@ -38,8 +38,8 @@
#define KINEMATIC_PLANNING_RPK_BASIC_REQUEST_LINK_POSITION_
#include "kinematic_planning/RKPBasicRequest.h"
-#include <robot_srvs/KinematicPlanLinkPosition.h>
-#include <robot_srvs/KinematicReplanLinkPosition.h>
+#include <motion_planning_srvs/KinematicPlanLinkPosition.h>
+#include <motion_planning_srvs/KinematicReplanLinkPosition.h>
namespace kinematic_planning
{
@@ -50,7 +50,7 @@
{
public:
- GoalToPosition(ompl::sb::SpaceInformationKinematic *si, RKPModelBase *model, const std::vector<robot_msgs::PoseConstraint> &pc) : ompl::sb::GoalRegion(si)
+ GoalToPosition(ompl::sb::SpaceInformationKinematic *si, RKPModelBase *model, const std::vector<motion_planning_msgs::PoseConstraint> &pc) : ompl::sb::GoalRegion(si)
{
m_model = model;
for (unsigned int i = 0 ; i < pc.size() ; ++i)
@@ -135,14 +135,14 @@
};
template<>
- RKPBasicRequest<robot_msgs::KinematicPlanLinkPositionRequest>::RKPBasicRequest(void)
+ RKPBasicRequest<motion_planning_msgs::KinematicPlanLinkPositionRequest>::RKPBasicRequest(void)
{
m_type = R_POSITION;
}
/** Validate request for planning towards a link position */
template<>
- bool RKPBasicRequest<robot_msgs::KinematicPlanLinkPositionRequest>::isRequestValid(ModelMap &models, robot_msgs::KinematicPlanLinkPositionRequest &req)
+ bool RKPBasicRequest<motion_planning_msgs::KinematicPlanLinkPositionRequest>::isRequestValid(ModelMap &models, motion_planning_msgs::KinematicPlanLinkPositionRequest &req)
{
if (!areSpaceParamsValid(models, req.params))
return false;
@@ -160,10 +160,10 @@
/** Set the goal using a destination link position */
template<>
- void RKPBasicRequest<robot_msgs::KinematicPlanLinkPositionRequest>::setupGoalState(RKPPlannerSetup *psetup, robot_msgs::KinematicPlanLinkPositionRequest &req)
+ void RKPBasicRequest<motion_planning_msgs::KinematicPlanLinkPositionRequest>::setupGoalState(RKPPlannerSetup *psetup, motion_planning_msgs::KinematicPlanLinkPositionRequest &req)
{
/* set the goal */
- std::vector<robot_msgs::PoseConstraint> pc;
+ std::vector<motion_planning_msgs::PoseConstraint> pc;
req.get_goal_constraints_vec(pc);
GoalToPosition *goal = new GoalToPosition(psetup->si, psetup->model, pc);
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestState.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestState.h 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPBasicRequestState.h 2009-05-11 21:22:55 UTC (rev 15190)
@@ -38,8 +38,8 @@
#define KINEMATIC_PLANNING_RKP_BASIC_REQUEST_STATE_
#include "kinematic_planning/RKPBasicRequest.h"
-#include <robot_srvs/KinematicPlanState.h>
-#include <robot_srvs/KinematicReplanState.h>
+#include <motion_planning_srvs/KinematicPlanState.h>
+#include <motion_planning_srvs/KinematicReplanState.h>
namespace kinematic_planning
{
@@ -47,14 +47,14 @@
static const int R_STATE = 1; // state request
template<>
- RKPBasicRequest<robot_msgs::KinematicPlanStateRequest>::RKPBasicRequest(void)
+ RKPBasicRequest<motion_planning_msgs::KinematicPlanStateRequest>::RKPBasicRequest(void)
{
m_type = R_STATE;
}
/** Validate request for planning towards a state */
template<>
- bool RKPBasicRequest<robot_msgs::KinematicPlanStateRequest>::isRequestValid(ModelMap &models, robot_msgs::KinematicPlanStateRequest &req)
+ bool RKPBasicRequest<motion_planning_msgs::KinematicPlanStateRequest>::isRequestValid(ModelMap &models, motion_planning_msgs::KinematicPlanStateRequest &req)
{
if (!areSpaceParamsValid(models, req.params))
return false;
@@ -79,7 +79,7 @@
/** Set the goal using a destination state */
template<>
- void RKPBasicRequest<robot_msgs::KinematicPlanStateRequest>::setupGoalState(RKPPlannerSetup *psetup, robot_msgs::KinematicPlanStateRequest &req)
+ void RKPBasicRequest<motion_planning_msgs::KinematicPlanStateRequest>::setupGoalState(RKPPlannerSetup *psetup, motion_planning_msgs::KinematicPlanStateRequest &req)
{
/* set the goal */
ompl::sb::GoalState *goal = new ompl::sb::GoalState(psetup->si);
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPConstraintEvaluator.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPConstraintEvaluator.h 2009-05-11 21:19:26 UTC (rev 15189)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPConstraintEvaluator.h 2009-05-11 21:22:55 UTC (rev 15190)
@@ -38,7 +38,7 @@
#define KINEMATIC_PLANNING_RKP_CONSTRAINT_EVALUATOR_
#include <planning_models/kinematic.h>
-#include <robot_msgs/KinematicConstraints.h>
+#include <motion_planning_msgs/KinematicConstraints.h>
#include <angles/angles.h>
#include <iostream>
#include <vector>
@@ -78,14 +78,14 @@
virtual bool use(planning_models::KinematicModel *kmodel, const ros::Message *kc)
{
- const robot_msgs::PoseConstraint *pc = dynamic_cast<const robot_msgs::PoseConstraint*>(kc);
+ const motion_planning_msgs::PoseConstraint *pc = dynamic_cast<const motion_planning_msgs::PoseConstraint*>(kc);
if (pc)
return use(kmodel, *pc);
else
return false;
}
- bool use(planning_models::KinematicModel *kmodel, const robot_msgs::PoseConstraint &pc)
+ bool use(planning_models::KinematicModel *kmodel, const motion_planning_msgs::PoseConstraint &pc)
{
m_link = kmodel->getLink(pc.robot_link);
m_pc = pc;
@@ -117,36 +117,36 @@
double dx, dy, dz;
switch (m_pc.type & 0xFF)
{
- case robot_msgs::PoseConstraint::POSITION_XYZ:
+ case motion_planning_msgs::PoseConstraint::POSITION_XYZ:
dx = bodyPos.getX() - m_pc.x;
dy = bodyPos.getY() - m_pc.y;
dz = bodyPos.getZ() - m_pc.z;
*distPos = dx * dx + dy * dy + dz * dz;
break;
- case robot_msgs::PoseConstraint::POSITION_XY:
+ case motion_planning_msgs::PoseConstraint::POSITION_XY:
dx = bodyPos.getX() - m_pc.x;
dy = bodyPos.getY() - m_pc.y;
*distPos = dx * dx + dy * dy;
break;
- case robot_msgs::PoseConstraint::POSITION_XZ:
+ case motion_planning_msgs::PoseConstraint::POSITION_XZ:
dx = bodyPos.getX() - m_pc.x;
dz = bodyPos.getZ() - m_pc.z;
*distPos = dx * dx + dz * dz;
break;
- case robot_msgs::PoseConstraint::POSITION_YZ:
+ case motion_planning_msgs::PoseConstraint::POSITION_YZ:
dy = bodyPos.getY() - m_pc.y;
dz = bodyPos.getZ() - m_pc.z;
*distPos = dy * dy + dz * dz;
break;
- case robot_msgs::PoseConstraint::POSITION_X:
+ case motion_planning_msgs::PoseConstraint::POSITION_X:
dx = bodyPos.getX() - m_pc.x;
*distPos = dx * dx;
break;
- case robot_msgs::PoseConstraint::POSITION_Y:
+ case motion_planning_msgs::PoseConstraint::POSITION_Y:
dy = bodyPos.getY() - m_pc.y;
*distPos = dy * dy;
break;
- case robot_msgs::PoseConstraint::POSITION_Z:
+ case motion_planning_msgs::PoseConstraint::POSITION_Z:
dz = bodyPos.getZ() - m_pc.z;
*distPos = dz * dz;
break;
@@ -166,30 +166,30 @@
m_link->globalTrans.getBasis().getEulerYPR(yaw, pitch, roll);
switch (m_pc.type & (~0xFF))
{
- case robot_msgs::PoseConstraint::ORIENTATION_RPY:
+ case motion_planning_msgs::PoseConstraint::ORIENTATION_RPY:
*distAng = fabs(angles::shortest_angular_distance(roll, m_pc.roll)) +
fabs(angles::shortest_angular_distance(pitch, m_pc.pitch)) +
fabs(angles::shortest_angular_distance(yaw, m_pc.yaw));
break;
- case robot_msgs::PoseConstraint::ORIENTATION_RP:
+ case motion_planning_msgs::PoseConstraint::ORIENTATION_RP:
*distAng = fabs(angles::shortest_angular_distance(roll, m_pc.roll)) +
fabs(angles::shortest_angular_distance(pitch, m_pc.pitch));
break;
- case robot_msgs::PoseConstraint::ORIENTATION_RY:
+ case motion_planning_msgs::PoseConstraint::ORIENTATION_RY:
*distAng = fabs(angles::shortest_angular_distance(roll, m_pc.roll)) +
fabs(angles::shortest_angular_distance(yaw, m_pc.yaw));
break;
- case robot_msgs::PoseConstraint::ORIENTATION_PY:
+ case motion_planning_msgs::PoseConstraint::ORIENTATION_PY:
*distAng = fabs(angles::shortest_angular_distance(pitch, m_pc.pitch)) +
fabs(angles::shortest_angular_distance(yaw, m_pc.yaw));
break;
- case robot_msgs::PoseConstraint::ORIENTATION_R:
+ case motion_planning_msgs:...
[truncated message content] |