80 ROS_WARN_STREAM(
"Param '" << ATTEMPTS_PARAM_NAME <<
"' needs to be at least 1.");
88 return "Fix Start State In Collision";
94 std::vector<std::size_t>& added_path_index)
const 99 robot_state::RobotState start_state = planning_scene->getCurrentState();
100 robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
105 planning_scene->checkCollision(creq, cres, start_state);
112 planning_scene->checkCollision(vcreq, vcres, start_state);
114 if (creq.group_name.empty())
115 ROS_INFO(
"Start state appears to be in collision");
117 ROS_INFO_STREAM(
"Start state appears to be in collision with respect to group " << creq.group_name);
119 robot_state::RobotStatePtr prefix_state(
new robot_state::RobotState(start_state));
122 const std::vector<const robot_model::JointModel*>& jmodels =
123 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
124 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
125 planning_scene->getRobotModel()->getJointModels();
130 for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
132 std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
133 const double* original_values = prefix_state->getJointPositions(jmodels[i]);
134 jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
136 start_state.setJointPositions(jmodels[i], sampled_variable_values);
138 planning_scene->checkCollision(creq, cres, start_state);
142 ROS_INFO(
"Found a valid state near the start state at distance %lf after %d attempts",
143 prefix_state->distance(start_state), c);
151 robot_state::robotStateToRobotStateMsg(start_state, req2.start_state);
152 bool solved = planner(planning_scene, req2, res);
159 res.
trajectory_->addPrefixWayPoint(prefix_state, 0.0);
161 for (std::size_t i = 0; i < added_path_index.size(); ++i)
162 added_path_index[i]++;
163 added_path_index.push_back(0);
169 ROS_WARN(
"Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %u sampling " 170 "attempts). Passing the original planning request to the planner.",
172 return planner(planning_scene, req, res);
177 if (creq.group_name.empty())
180 ROS_DEBUG_STREAM(
"Start state is valid with respect to group " << creq.group_name);
181 return planner(planning_scene, req, res);
robot_trajectory::RobotTrajectoryPtr trajectory_
static const std::string ATTEMPTS_PARAM_NAME
static const std::string JIGGLE_PARAM_NAME
static const std::string DT_PARAM_NAME
virtual std::string getDescription() const
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
moveit_msgs::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateCollision, planning_request_adapter::PlanningRequestAdapter)
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const