40 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
48 rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.fix_start_state_path_constraints");
57 void initialize(
const rclcpp::Node::SharedPtr& ,
const std::string& )
override
63 return "Fix Start State Path Constraints";
68 std::vector<std::size_t>& added_path_index)
const override
78 !
planning_scene->isStateValid(start_state, req.path_constraints, req.group_name))
80 RCLCPP_INFO(LOGGER,
"Path constraints not satisfied for start state...");
81 planning_scene->isStateValid(start_state, req.path_constraints, req.group_name,
true);
82 RCLCPP_INFO(LOGGER,
"Planning to path constraints...");
85 req2.goal_constraints.resize(1);
86 req2.goal_constraints[0] = req.path_constraints;
87 req2.path_constraints = moveit_msgs::msg::Constraints();
91 std::vector<std::size_t> added_path_index_temp;
92 added_path_index_temp.swap(added_path_index);
94 added_path_index_temp.swap(added_path_index);
99 RCLCPP_INFO(LOGGER,
"Planned to path constraints. Resuming original planning request.");
109 for (std::size_t& added_index : added_path_index)
110 added_index += res2.
trajectory_->getWayPointCount();
113 for (std::size_t i = 0; i < res2.
trajectory_->getWayPointCount(); ++i)
114 added_path_index.push_back(i);
126 RCLCPP_WARN(LOGGER,
"Unable to plan to path constraints. Running usual motion plan.");
134 RCLCPP_DEBUG(LOGGER,
"Path constraints are OK. Running usual motion plan.");
FixStartStatePathConstraints()
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.
void initialize(const rclcpp::Node::SharedPtr &, const std::string &) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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
Generic interface to adapting motion planning requests.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)