39 #include <moveit_msgs/DisplayTrajectory.h>
40 #include <visualization_msgs/MarkerArray.h>
52 : pick_place_(
pick_place), pipeline_(
name, 4), last_plan_time_(0.0), done_(false)
93 : nh_(
"~"), planning_pipeline_(
planning_pipeline), display_computed_motion_plans_(false), display_grasps_(false)
95 constraint_sampler_manager_loader_ =
96 std::make_shared<constraint_sampler_manager_loader::ConstraintSamplerManagerLoader>();
119 moveit_msgs::DisplayTrajectory dtraj;
131 dtraj.trajectory.resize(dtraj.trajectory.size() + 1);
132 traj.
trajectory_->getRobotTrajectoryMsg(dtraj.trajectory.back());
144 std::vector<std_msgs::ColorRGBA> setupDefaultGraspColors()
146 std::vector<std_msgs::ColorRGBA> result;
184 static std::vector<std_msgs::ColorRGBA> colors(setupDefaultGraspColors());
185 visualization_msgs::MarkerArray ma;
186 for (
const ManipulationPlanPtr& plan : plans)
191 unsigned int type = std::min(plan->processing_stage_, colors.size() - 1);
194 "moveit_grasps:stage_" + boost::lexical_cast<std::string>(plan->processing_stage_),