40 #include <class_loader/class_loader.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/node.hpp>
44 #include <rclcpp/parameter_value.hpp>
48 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.fix_start_state_collision");
57 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
63 if (sampling_attempts_ < 1)
65 sampling_attempts_ = 1;
72 return "Fix Start State In Collision";
77 std::vector<std::size_t>& added_path_index)
const override
98 RCLCPP_INFO(LOGGER,
"Start state appears to be in collision");
100 RCLCPP_INFO(LOGGER,
"Start state appears to be in collision with respect to group %s", creq.
group_name.c_str());
102 auto prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
103 random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
105 const std::vector<const moveit::core::JointModel*>& jmodels =
106 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
107 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
111 for (
int c = 0; !found &&
c < sampling_attempts_; ++
c)
113 for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
115 std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
116 const double* original_values = prefix_state->getJointPositions(jmodels[i]);
117 jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
118 jmodels[i]->getMaximumExtent() * jiggle_fraction_);
125 RCLCPP_INFO(LOGGER,
"Found a valid state near the start state at distance %lf after %d attempts",
126 prefix_state->distance(start_state),
c);
140 res.
trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_,
142 res.
trajectory_->addPrefixWayPoint(prefix_state, 0.0);
144 for (std::size_t& added_index : added_path_index)
146 added_path_index.push_back(0);
153 "Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %u sampling "
154 "attempts). Passing the original planning request to the planner.",
155 jiggle_fraction_, sampling_attempts_);
162 RCLCPP_DEBUG(LOGGER,
"Start state is valid");
164 RCLCPP_DEBUG(LOGGER,
"Start state is valid with respect to group %s", creq.
group_name.c_str());
170 rclcpp::Node::SharedPtr node_;
171 double max_dt_offset_;
172 double jiggle_fraction_;
173 int sampling_attempts_;
static const std::string ATTEMPTS_PARAM_NAME
static const std::string DT_PARAM_NAME
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
static const std::string JIGGLE_PARAM_NAME
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 override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointPositions(const std::string &joint_name, const double *position)
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string ¶meter_namespace, const std::string ¶meter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
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.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
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.
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)