plan_stage.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
40 #include <ros/console.h>
41 
42 namespace pick_place
43 {
44 PlanStage::PlanStage(const planning_scene::PlanningSceneConstPtr& scene,
45  const planning_pipeline::PlanningPipelinePtr& planning_pipeline)
46  : ManipulationStage("plan"), planning_scene_(scene), planning_pipeline_(planning_pipeline)
47 {
48 }
49 
51 {
53  planning_pipeline_->terminate();
54 }
55 
56 // Plan the arm movement to the approach location
57 bool PlanStage::evaluate(const ManipulationPlanPtr& plan) const
58 {
61  req.group_name = plan->shared_data_->planning_group_->getName();
62  req.num_planning_attempts = 1;
63  req.allowed_planning_time = (plan->shared_data_->timeout_ - ros::WallTime::now()).toSec();
64  req.path_constraints = plan->shared_data_->path_constraints_;
65  req.planner_id = plan->shared_data_->planner_id_;
66  req.start_state.is_diff = true;
67 
68  req.goal_constraints.resize(1, kinematic_constraints::constructGoalConstraints(*plan->approach_state_,
69  plan->shared_data_->planning_group_));
70  unsigned int attempts = 0;
71  do // give the planner two chances
72  {
73  attempts++;
74  if (!signal_stop_ && planning_pipeline_->generatePlan(planning_scene_, req, res) &&
75  res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS && res.trajectory_ && !res.trajectory_->empty())
76  {
77  // We have a valid motion plan, now apply pre-approach end effector posture (open gripper) if applicable
78  if (!plan->approach_posture_.joint_names.empty())
79  {
80  moveit::core::RobotStatePtr pre_approach_state(new moveit::core::RobotState(res.trajectory_->getLastWayPoint()));
81  robot_trajectory::RobotTrajectoryPtr pre_approach_traj(new robot_trajectory::RobotTrajectory(
82  pre_approach_state->getRobotModel(), plan->shared_data_->end_effector_group_->getName()));
83  pre_approach_traj->setRobotTrajectoryMsg(*pre_approach_state, plan->approach_posture_);
84 
85  // Apply the open gripper state to the waypoint
86  // If user has defined a time for it's gripper movement time, don't add the
87  // DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
88  if (!plan->approach_posture_.points.empty() &&
89  plan->approach_posture_.points.back().time_from_start > ros::Duration(0.0))
90  {
91  pre_approach_traj->addPrefixWayPoint(pre_approach_state, 0.0);
92  }
93  else
94  { // Do what was done before
96  << " seconds to the grasp closure time. Assign time_from_start "
97  << "to your trajectory to avoid this.");
98  pre_approach_traj->addPrefixWayPoint(pre_approach_state, PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION);
99  }
100 
101  // Add the open gripper trajectory to the plan
102  plan_execution::ExecutableTrajectory et(pre_approach_traj, "pre_grasp");
103  plan->trajectories_.insert(plan->trajectories_.begin(), et);
104  }
105 
106  // Add the pre-approach trajectory to the plan
108  plan->trajectories_.insert(plan->trajectories_.begin(), et);
109 
110  plan->error_code_ = res.error_code_;
111 
112  return true;
113  }
114  else
115  plan->error_code_ = res.error_code_;
116  }
117  // if the planner reported an invalid plan, give it a second chance
118  while (!signal_stop_ && plan->error_code_.val == moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN && attempts < 2);
119 
120  return false;
121 }
122 } // namespace pick_place
pick_place
Definition: approach_and_translate_stage.h:43
pick_place::PlanStage::planning_scene_
planning_scene::PlanningSceneConstPtr planning_scene_
Definition: plan_stage.h:120
planning_interface::MotionPlanResponse
utils.h
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
kinematic_constraints::constructGoalConstraints
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
moveit::core::RobotState
robot_trajectory::RobotTrajectory
pick_place.h
plan_stage.h
pick_place::ManipulationStage::signalStop
virtual void signalStop()
Definition: manipulation_stage.h:105
console.h
pick_place::PlanStage::signalStop
void signalStop() override
Definition: plan_stage.cpp:82
pick_place::PlanStage::PlanStage
PlanStage(const planning_scene::PlanningSceneConstPtr &scene, const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
Definition: plan_stage.cpp:76
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
ros::WallTime::now
static WallTime now()
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
plan_execution::ExecutableTrajectory
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
pick_place::PlanStage::evaluate
bool evaluate(const ManipulationPlanPtr &plan) const override
Definition: plan_stage.cpp:89
planning_pipeline
pick_place::PlanStage::planning_pipeline_
planning_pipeline::PlanningPipelinePtr planning_pipeline_
Definition: plan_stage.h:121
pick_place::PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
Definition: pick_place.h:152
planning_interface::MotionPlanResponse::planner_id_
std::string planner_id_
ros::Duration
pick_place::ManipulationStage::name_
std::string name_
Definition: manipulation_stage.h:113
pick_place::ManipulationStage::signal_stop_
bool signal_stop_
Definition: manipulation_stage.h:114


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:51