Skip to content

Commit

Permalink
Extend MotionPlanRequest with seed trajectories
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar committed Jul 7, 2018
1 parent 3667e9d commit d79229b
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ DisplayRobotState.msg
Grasp.msg
GripperTranslation.msg
JointConstraint.msg
JointOrCartesianTrajectory.msg
JointLimits.msg
LinkPadding.msg
LinkScale.msg
Expand Down
3 changes: 3 additions & 0 deletions msg/JointOrCartesianTrajectory.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
Header header
trajectory_msgs/JointTrajectory joint_trajectory
geometry_msgs/TransformStamped[] cartesian_trajectory
3 changes: 3 additions & 0 deletions msg/MotionPlanRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@ Constraints path_constraints
# The constraints the resulting trajectory must satisfy
TrajectoryConstraints trajectory_constraints

# A set of trajectories to be used as seed trajectories for optimization-based planners
JointOrCartesianTrajectory[] seed_trajectories

# The name of the motion planner to use. If no name is specified,
# a default motion planner will be used
string planner_id
Expand Down

0 comments on commit d79229b

Please sign in to comment.