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;
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;