42 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"local_planner_component");
44 constexpr
size_t STUCK_ITERATIONS_THRESHOLD = 5;
45 constexpr
double STUCK_THRESHOLD_RAD = 1e-4;
55 if (node->has_parameter(
"stop_before_collision"))
56 node->get_parameter<
bool>(
"stop_before_collision", stop_before_collision_);
58 stop_before_collision_ = node->declare_parameter<
bool>(
"stop_before_collision",
false);
61 path_invalidation_event_send_ =
false;
62 num_iterations_stuck_ = 0;
68 num_iterations_stuck_ = 0;
69 prev_waypoint_target_.reset();
70 path_invalidation_event_send_ =
false;
74 moveit_msgs::action::LocalPlanner::Feedback
76 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> ,
77 trajectory_msgs::msg::JointTrajectory& local_solution)
80 RCLCPP_INFO_THROTTLE(LOGGER, *node_->get_clock(), 2000 ,
"The local planner is solving...");
86 moveit_msgs::action::LocalPlanner::Feedback feedback_result;
89 if (!stop_before_collision_)
96 planning_scene_monitor_->updateFrameTransforms();
98 moveit::core::RobotStatePtr current_state;
99 bool is_path_valid =
false;
103 current_state = std::make_shared<moveit::core::RobotState>(locked_planning_scene->getCurrentState());
104 is_path_valid = locked_planning_scene->isPathValid(local_trajectory, local_trajectory.
getGroupName(),
false);
110 if (path_invalidation_event_send_)
112 path_invalidation_event_send_ =
false;
119 if (!path_invalidation_event_send_)
122 path_invalidation_event_send_ =
true;
124 RCLCPP_INFO(LOGGER,
"Collision ahead, holding current position");
135 robot_command.
empty();
140 if (!prev_waypoint_target_)
147 if (prev_waypoint_target_->distance(*robot_command.
getFirstWayPointPtr()) <= STUCK_THRESHOLD_RAD)
149 ++num_iterations_stuck_;
150 if (num_iterations_stuck_ > STUCK_ITERATIONS_THRESHOLD)
152 num_iterations_stuck_ = 0;
153 prev_waypoint_target_ =
nullptr;
155 path_invalidation_event_send_ =
true;
156 RCLCPP_INFO(LOGGER,
"The local planner has been stuck for several iterations. Aborting.");
164 moveit_msgs::msg::RobotTrajectory robot_command_msg;
166 local_solution = robot_command_msg.joint_trajectory;
168 return feedback_result;
172 #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)
const rclcpp::Logger LOGGER