43 constexpr
size_t STUCK_ITERATIONS_THRESHOLD = 5;
44 constexpr
double STUCK_THRESHOLD_RAD = 1e-4;
54 if (node->has_parameter(
"stop_before_collision"))
56 node->get_parameter<
bool>(
"stop_before_collision", stop_before_collision_);
60 stop_before_collision_ = node->declare_parameter<
bool>(
"stop_before_collision",
false);
63 path_invalidation_event_send_ =
false;
64 num_iterations_stuck_ = 0;
73 num_iterations_stuck_ = 0;
74 prev_waypoint_target_.reset();
75 path_invalidation_event_send_ =
false;
79 moveit_msgs::action::LocalPlanner::Feedback
81 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> ,
82 trajectory_msgs::msg::JointTrajectory& local_solution)
85 #pragma GCC diagnostic push
86 #pragma GCC diagnostic ignored "-Wold-style-cast"
87 RCLCPP_INFO_THROTTLE(node_->get_logger(), *node_->get_clock(), 2000 ,
"The local planner is solving...");
88 #pragma GCC diagnostic pop
94 moveit_msgs::action::LocalPlanner::Feedback feedback_result;
97 if (!stop_before_collision_)
104 planning_scene_monitor_->updateFrameTransforms();
106 moveit::core::RobotStatePtr current_state;
107 bool is_path_valid =
false;
110 planning_scene_monitor_->updateSceneWithCurrentState();
112 current_state = std::make_shared<moveit::core::RobotState>(locked_planning_scene->getCurrentState());
113 is_path_valid = locked_planning_scene->isPathValid(local_trajectory, local_trajectory.
getGroupName(),
false);
119 if (path_invalidation_event_send_)
121 path_invalidation_event_send_ =
false;
128 if (!path_invalidation_event_send_)
131 path_invalidation_event_send_ =
true;
133 RCLCPP_INFO(node_->get_logger(),
"Collision ahead, holding current position");
144 robot_command.
empty();
149 if (!prev_waypoint_target_)
156 if (prev_waypoint_target_->distance(*robot_command.
getFirstWayPointPtr()) <= STUCK_THRESHOLD_RAD)
158 ++num_iterations_stuck_;
159 if (num_iterations_stuck_ > STUCK_ITERATIONS_THRESHOLD)
161 num_iterations_stuck_ = 0;
162 prev_waypoint_target_ =
nullptr;
164 path_invalidation_event_send_ =
true;
165 RCLCPP_INFO(node_->get_logger(),
"The local planner has been stuck for several iterations. Aborting.");
173 moveit_msgs::msg::RobotTrajectory robot_command_msg;
175 local_solution = robot_command_msg.joint_trajectory;
177 return feedback_result;
181 #include <pluginlib/class_list_macros.hpp>
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void zeroVelocities()
Set all velocities to 0.0.
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
void zeroAccelerations()
Set all accelerations to 0.0.
moveit_msgs::action::LocalPlanner::Feedback solve(const robot_trajectory::RobotTrajectory &local_trajectory, const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal >, trajectory_msgs::msg::JointTrajectory &local_solution) override
bool initialize(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const std::string &) override
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
const std::string & getGroupName() const
const moveit::core::RobotModelConstPtr & getRobotModel() const
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
double getWayPointDurationFromPrevious(std::size_t index) const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
moveit::core::RobotStatePtr & getFirstWayPointPtr()
PLUGINLIB_EXPORT_CLASS(moveit::hybrid_planning::ForwardTrajectory, moveit::hybrid_planning::LocalConstraintSolverInterface)
constexpr std::string_view toString(const LocalFeedbackEnum &code)