pick_place.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 
39 #include <moveit_msgs/DisplayTrajectory.h>
40 #include <visualization_msgs/MarkerArray.h>
41 
42 namespace pick_place
43 {
45 const std::string PickPlace::DISPLAY_GRASP_TOPIC = "display_grasp_markers";
46 const double PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION = 7.0; // seconds
47 
48 // functionality specific to pick-only is in pick.cpp;
49 // functionality specific to place-only is in place.cpp;
50 
51 PickPlacePlanBase::PickPlacePlanBase(const PickPlaceConstPtr& pick_place, const std::string& name)
52  : pick_place_(pick_place), pipeline_(name, 4), last_plan_time_(0.0), done_(false)
53 {
56 }
57 
59 
61 {
62  boost::mutex::scoped_lock slock(done_mutex_);
63  done_ = true;
64  done_condition_.notify_all();
65 }
66 
68 {
69  boost::mutex::scoped_lock slock(done_mutex_);
71  {
72  done_ = true;
73  done_condition_.notify_all();
74  }
75 }
76 
78 {
79  done_ = false;
80  pushed_all_poses_ = false;
81 }
82 
84 {
85  // wait till we're done
86  boost::unique_lock<boost::mutex> lock(done_mutex_);
87  pushed_all_poses_ = true;
88  while (!done_ && endtime > ros::WallTime::now())
89  done_condition_.timed_wait(lock, (endtime - ros::WallTime::now()).toBoost());
90 }
91 
92 PickPlace::PickPlace(const planning_pipeline::PlanningPipelinePtr& planning_pipeline)
93  : nh_("~"), planning_pipeline_(planning_pipeline), display_computed_motion_plans_(false), display_grasps_(false)
94 {
95  constraint_sampler_manager_loader_ =
96  std::make_shared<constraint_sampler_manager_loader::ConstraintSamplerManagerLoader>();
97 }
98 
100 {
101  if (display_grasps_ && !flag)
103  else if (!display_grasps_ && flag)
104  grasps_publisher_ = nh_.advertise<visualization_msgs::MarkerArray>(DISPLAY_GRASP_TOPIC, 10, true);
105  display_grasps_ = flag;
106 }
107 
109 {
110  if (display_computed_motion_plans_ && !flag)
112  else if (!display_computed_motion_plans_ && flag)
113  display_path_publisher_ = nh_.advertise<moveit_msgs::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10, true);
115 }
116 
117 void PickPlace::visualizePlan(const ManipulationPlanPtr& plan) const
118 {
119  moveit_msgs::DisplayTrajectory dtraj;
120  dtraj.model_id = getRobotModel()->getName();
121  bool first = true;
122  for (const plan_execution::ExecutableTrajectory& traj : plan->trajectories_)
123  {
124  if (!traj.trajectory_ || traj.trajectory_->empty())
125  continue;
126  if (first)
127  {
128  moveit::core::robotStateToRobotStateMsg(traj.trajectory_->getFirstWayPoint(), dtraj.trajectory_start);
129  first = false;
130  }
131  dtraj.trajectory.resize(dtraj.trajectory.size() + 1);
132  traj.trajectory_->getRobotTrajectoryMsg(dtraj.trajectory.back());
133  }
135 }
136 
137 void PickPlace::visualizeGrasp(const ManipulationPlanPtr& plan) const
138 {
139  visualizeGrasps(std::vector<ManipulationPlanPtr>(1, plan));
140 }
141 
142 namespace
143 {
144 std::vector<std_msgs::ColorRGBA> setupDefaultGraspColors()
145 {
146  std::vector<std_msgs::ColorRGBA> result;
147  result.resize(6);
148  result[0].r = 0.5f;
149  result[0].g = 0.5f;
150  result[0].b = 0.5f;
151  result[0].a = 1.0f;
152  result[1].r = 1.0f;
153  result[1].g = 0.0f;
154  result[1].b = 0.0f;
155  result[1].a = 1.0f;
156  result[2].r = 1.0f;
157  result[2].g = 0.5f;
158  result[2].b = 0.0f;
159  result[2].a = 1.0f;
160  result[3].r = 0.0f;
161  result[3].g = 1.0f;
162  result[3].b = 1.0f;
163  result[3].a = 1.0f;
164  result[4].r = 0.0f;
165  result[4].g = 1.0f;
166  result[4].b = 0.0f;
167  result[4].a = 1.0f;
168  result[5].r = 1.0f;
169  result[5].g = 0.0f;
170  result[5].b = 1.0f;
171  result[5].a = 0.75f;
172  return result;
173 }
174 } // namespace
175 
176 void PickPlace::visualizeGrasps(const std::vector<ManipulationPlanPtr>& plans) const
177 {
178  if (plans.empty())
179  return;
180 
182  state.setToDefaultValues();
183 
184  static std::vector<std_msgs::ColorRGBA> colors(setupDefaultGraspColors());
185  visualization_msgs::MarkerArray ma;
186  for (const ManipulationPlanPtr& plan : plans)
187  {
188  const moveit::core::JointModelGroup* jmg = plan->shared_data_->end_effector_group_;
189  if (jmg)
190  {
191  unsigned int type = std::min(plan->processing_stage_, colors.size() - 1);
192  state.updateStateWithLinkAt(plan->shared_data_->ik_link_, plan->transformed_goal_pose_);
193  state.getRobotMarkers(ma, jmg->getLinkModelNames(), colors[type],
194  "moveit_grasps:stage_" + boost::lexical_cast<std::string>(plan->processing_stage_),
195  ros::Duration(60));
196  }
197  }
198 
200 }
201 } // namespace pick_place
pick_place::PickPlace::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: pick_place.h:166
pick_place
Definition: approach_and_translate_stage.h:43
pick_place::PickPlacePlanBase::pushed_all_poses_
bool pushed_all_poses_
Definition: pick_place.h:121
pick_place::PickPlace::displayProcessedGrasps
void displayProcessedGrasps(bool flag)
Definition: pick_place.cpp:131
planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC
static const std::string DISPLAY_PATH_TOPIC
pick_place::PickPlacePlanBase::done_mutex_
boost::mutex done_mutex_
Definition: pick_place.h:123
pick_place::PickPlace::display_grasps_
bool display_grasps_
Definition: pick_place.h:192
moveit::core::RobotState::getRobotMarkers
void getRobotMarkers(visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, bool include_attached=false)
moveit::core::RobotState
plan_execution::ExecutableTrajectory::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
pick_place::PickPlace::nh_
ros::NodeHandle nh_
Definition: pick_place.h:189
pick_place::PickPlacePlanBase::initialize
void initialize()
Definition: pick_place.cpp:109
pick_place.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
pick_place::PickPlace::display_computed_motion_plans_
bool display_computed_motion_plans_
Definition: pick_place.h:191
pick_place::PickPlacePlanBase::pipeline_
ManipulationPipeline pipeline_
Definition: pick_place.h:117
pick_place::PickPlace::display_path_publisher_
ros::Publisher display_path_publisher_
Definition: pick_place.h:193
name
std::string name
ros::Publisher::shutdown
void shutdown()
pick_place::PickPlace::DISPLAY_GRASP_TOPIC
static const std::string DISPLAY_GRASP_TOPIC
Definition: pick_place.h:149
pick_place::PickPlace::DISPLAY_PATH_TOPIC
static const std::string DISPLAY_PATH_TOPIC
Definition: pick_place.h:148
pick_place::ManipulationPipeline::setEmptyQueueCallback
void setEmptyQueueCallback(const boost::function< void()> &callback)
Definition: manipulation_pipeline.h:128
ros::WallTime::now
static WallTime now()
pick_place::PickPlacePlanBase::foundSolution
void foundSolution()
Definition: pick_place.cpp:92
moveit::core::RobotState::setToDefaultValues
void setToDefaultValues()
pick_place::PickPlace::visualizeGrasp
void visualizeGrasp(const ManipulationPlanPtr &plan) const
Definition: pick_place.cpp:169
pick_place::PickPlacePlanBase::emptyQueue
void emptyQueue()
Definition: pick_place.cpp:99
pick_place::PickPlacePlanBase::done_condition_
boost::condition_variable done_condition_
Definition: pick_place.h:122
plan_execution::ExecutableTrajectory
ros::WallTime
pick_place::PickPlacePlanBase::~PickPlacePlanBase
~PickPlacePlanBase()
planning_pipeline
pick_place::PickPlace::grasps_publisher_
ros::Publisher grasps_publisher_
Definition: pick_place.h:194
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
pick_place::ManipulationPipeline::setSolutionCallback
void setSolutionCallback(const boost::function< void()> &callback)
Definition: manipulation_pipeline.h:123
pick_place::PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
Definition: pick_place.h:152
pick_place::PickPlace::visualizeGrasps
void visualizeGrasps(const std::vector< ManipulationPlanPtr > &plans) const
Definition: pick_place.cpp:208
pick_place::PickPlace::displayComputedMotionPlans
void displayComputedMotionPlans(bool flag)
Definition: pick_place.cpp:140
moveit::core::JointModelGroup
conversions.h
moveit::core::RobotState::updateStateWithLinkAt
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false)
pick_place::PickPlace::visualizePlan
void visualizePlan(const ManipulationPlanPtr &plan) const
Definition: pick_place.cpp:149
pick_place::PickPlacePlanBase::waitForPipeline
void waitForPipeline(const ros::WallTime &endtime)
Definition: pick_place.cpp:115
pick_place::PickPlacePlanBase::PickPlacePlanBase
PickPlacePlanBase(const PickPlaceConstPtr &pick_place, const std::string &name)
Definition: pick_place.cpp:83
ros::Duration
pick_place::PickPlace::PickPlace
PickPlace(const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
Definition: pick_place.cpp:124
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
pick_place::PickPlacePlanBase::done_
bool done_
Definition: pick_place.h:120


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