54   bool initialize(
const moveit::core::RobotModelConstPtr& model, 
const std::string& ns)
 override 
   60     for (
const std::string& group : model->getJointModelGroupNames())
 
   62       planning_contexts_[group] = std::make_shared<CHOMPPlanningContext>(
"chomp_planning_context", group, model, nh);
 
   69                                                             moveit_msgs::MoveItErrorCodes& error_code)
 const override 
   71     error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
 
   73     if (req.group_name.empty())
 
   75       ROS_ERROR(
"No group specified to plan for");
 
   76       error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
 
   77       return planning_interface::PlanningContextPtr();
 
   82       ROS_ERROR(
"No planning scene supplied as input");
 
   83       error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
 
   84       return planning_interface::PlanningContextPtr();
 
   93     context->setPlanningScene(ps);
 
   94     context->setMotionPlanRequest(req);
 
   95     error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;