46 #include <class_loader/class_loader.hpp>
47 #include <rclcpp/logger.hpp>
48 #include <rclcpp/logging.hpp>
49 #include <rclcpp/node.hpp>
50 #include <rclcpp/parameter_value.hpp>
53 #include <default_plan_request_adapter_parameters.hpp>
67 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
70 std::make_unique<default_plan_request_adapter_parameters::ParamListener>(node, parameter_namespace);
75 return "Fix Start State In Collision";
102 RCLCPP_INFO(logger_,
"Start state appears to be in collision");
106 RCLCPP_INFO(logger_,
"Start state appears to be in collision with respect to group %s", creq.
group_name.c_str());
109 auto prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
110 random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
112 const std::vector<const moveit::core::JointModel*>& jmodels =
113 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
114 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
118 const auto params = param_listener_->get_params();
120 for (
int c = 0; !found && c < params.max_sampling_attempts; ++c)
122 for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
124 std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
125 const double* original_values = prefix_state->getJointPositions(jmodels[i]);
126 jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
127 jmodels[i]->getMaximumExtent() * params.jiggle_fraction);
134 RCLCPP_INFO(logger_,
"Found a valid state near the start state at distance %lf after %d attempts",
135 prefix_state->distance(start_state), c);
149 res.
trajectory->setWayPointDurationFromPrevious(0, std::min(params.start_state_max_dt,
150 res.
trajectory->getAverageSegmentDuration()));
151 res.
trajectory->addPrefixWayPoint(prefix_state, 0.0);
165 "Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %lu sampling "
166 "attempts). Passing the original planning request to the planner.",
167 params.jiggle_fraction, params.max_sampling_attempts);
168 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_IN_COLLISION;
176 RCLCPP_DEBUG(logger_,
"Start state is valid");
180 RCLCPP_DEBUG(logger_,
"Start state is valid with respect to group %s", creq.
group_name.c_str());
187 std::unique_ptr<default_plan_request_adapter_parameters::ParamListener> param_listener_;
188 rclcpp::Logger logger_;
This fix start state collision adapter will attempt to sample a new collision-free configuration near...
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::string getDescription() const override
Get a description of this adapter.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointPositions(const std::string &joint_name, const double *position)
Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-proc...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Functional interface to call a planning function.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
Main namespace for MoveIt.
rclcpp::Logger makeChildLogger(const std::string &name)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
std::vector< std::size_t > added_path_index
robot_trajectory::RobotTrajectoryPtr trajectory