39 #include <moveit_msgs/DisplayTrajectory.h> 40 #include <visualization_msgs/MarkerArray.h> 54 : pick_place_(pick_place), pipeline_(name, 4), last_plan_time_(0.0), done_(false)
97 : nh_(
"~"), planning_pipeline_(planning_pipeline), display_computed_motion_plans_(false), display_grasps_(false)
122 moveit_msgs::DisplayTrajectory dtraj;
125 for (std::size_t i = 0; i < plan->trajectories_.size(); ++i)
127 if (!plan->trajectories_[i].trajectory_ || plan->trajectories_[i].trajectory_->empty())
131 robot_state::robotStateToRobotStateMsg(plan->trajectories_[i].trajectory_->getFirstWayPoint(),
132 dtraj.trajectory_start);
135 dtraj.trajectory.resize(dtraj.trajectory.size() + 1);
136 plan->trajectories_[i].trajectory_->getRobotTrajectoryMsg(dtraj.trajectory.back());
148 std::vector<std_msgs::ColorRGBA> setupDefaultGraspColors()
150 std::vector<std_msgs::ColorRGBA> result;
186 state.setToDefaultValues();
188 static std::vector<std_msgs::ColorRGBA> colors(setupDefaultGraspColors());
189 visualization_msgs::MarkerArray ma;
190 for (std::size_t i = 0; i < plans.size(); ++i)
192 const robot_model::JointModelGroup* jmg = plans[i]->shared_data_->end_effector_group_;
195 unsigned int type = std::min(plans[i]->processing_stage_, colors.size() - 1);
196 state.updateStateWithLinkAt(plans[i]->shared_data_->ik_link_, plans[i]->transformed_goal_pose_);
197 state.getRobotMarkers(ma, jmg->getLinkModelNames(), colors[type],
198 "moveit_grasps:stage_" + boost::lexical_cast<std::string>(plans[i]->processing_stage_),
ros::Publisher display_path_publisher_
void notify_all() BOOST_NOEXCEPT
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
static const std::string DISPLAY_GRASP_TOPIC
void publish(const boost::shared_ptr< M > &message) const
boost::condition_variable done_condition_
void displayComputedMotionPlans(bool flag)
ros::Publisher grasps_publisher_
static const std::string DISPLAY_PATH_TOPIC
void displayProcessedGrasps(bool flag)
void visualizeGrasp(const ManipulationPlanPtr &plan) const
void setEmptyQueueCallback(const boost::function< void()> &callback)
void visualizeGrasps(const std::vector< ManipulationPlanPtr > &plans) const
ManipulationPipeline pipeline_
void waitForPipeline(const ros::WallTime &endtime)
const robot_model::RobotModelConstPtr & getRobotModel() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool display_computed_motion_plans_
static const std::string DISPLAY_PATH_TOPIC
void visualizePlan(const ManipulationPlanPtr &plan) const
PickPlace(const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
PickPlacePlanBase(const PickPlaceConstPtr &pick_place, const std::string &name)
void setSolutionCallback(const boost::function< void()> &callback)
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION