moveit2
The MoveIt Motion Planning Framework for ROS 2.
forward_trajectory.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
39 
40 namespace
41 {
42 const rclcpp::Logger LOGGER = rclcpp::get_logger("local_planner_component");
43 // If stuck for this many iterations or more, abort the local planning action
44 constexpr size_t STUCK_ITERATIONS_THRESHOLD = 5;
45 constexpr double STUCK_THRESHOLD_RAD = 1e-4; // L1-norm sum across all joints
46 } // namespace
47 
49 {
50 bool ForwardTrajectory::initialize(const rclcpp::Node::SharedPtr& node,
51  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
52  const std::string& /* unused */)
53 {
54  // Load parameter & initialize member variables
55  if (node->has_parameter("stop_before_collision"))
56  node->get_parameter<bool>("stop_before_collision", stop_before_collision_);
57  else
58  stop_before_collision_ = node->declare_parameter<bool>("stop_before_collision", false);
59  planning_scene_monitor_ = planning_scene_monitor;
60  node_ = node;
61  path_invalidation_event_send_ = false;
62  num_iterations_stuck_ = 0;
63  return true;
64 }
65 
67 {
68  num_iterations_stuck_ = 0;
69  prev_waypoint_target_.reset();
70  path_invalidation_event_send_ = false;
71  return true;
72 };
73 
74 moveit_msgs::action::LocalPlanner::Feedback
76  const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> /* unused */,
77  trajectory_msgs::msg::JointTrajectory& local_solution)
78 {
79  // A message every once in awhile is useful in case the local planner gets stuck
80  RCLCPP_INFO_THROTTLE(LOGGER, *node_->get_clock(), 2000 /* ms */, "The local planner is solving...");
81 
82  // Create controller command trajectory
83  robot_trajectory::RobotTrajectory robot_command(local_trajectory.getRobotModel(), local_trajectory.getGroupName());
84 
85  // Feedback
86  moveit_msgs::action::LocalPlanner::Feedback feedback_result;
87 
88  // If this flag is set, ignore collisions
89  if (!stop_before_collision_)
90  {
91  robot_command.addSuffixWayPoint(local_trajectory.getWayPoint(0), 0.0);
92  }
93  else
94  {
95  // Get current planning scene
96  planning_scene_monitor_->updateFrameTransforms();
97 
98  moveit::core::RobotStatePtr current_state;
99  bool is_path_valid = false;
100  // Lock the planning scene as briefly as possible
101  {
102  planning_scene_monitor::LockedPlanningSceneRO locked_planning_scene(planning_scene_monitor_);
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);
105  }
106 
107  // Check if path is valid
108  if (is_path_valid)
109  {
110  if (path_invalidation_event_send_)
111  {
112  path_invalidation_event_send_ = false; // Reset flag
113  }
114  // Forward next waypoint to the robot controller
115  robot_command.addSuffixWayPoint(local_trajectory.getWayPoint(0), 0.0);
116  }
117  else
118  {
119  if (!path_invalidation_event_send_)
120  { // Send feedback only once
121  feedback_result.feedback = toString(LocalFeedbackEnum::COLLISION_AHEAD);
122  path_invalidation_event_send_ = true; // Set feedback flag
123  }
124  RCLCPP_INFO(LOGGER, "Collision ahead, holding current position");
125  // Keep current position
126  moveit::core::RobotState current_state_command(*current_state);
127  if (current_state_command.hasVelocities())
128  {
129  current_state_command.zeroVelocities();
130  }
131  if (current_state_command.hasAccelerations())
132  {
133  current_state_command.zeroAccelerations();
134  }
135  robot_command.empty();
136  robot_command.addSuffixWayPoint(*current_state, local_trajectory.getWayPointDurationFromPrevious(0));
137  }
138 
139  // Detect if the local solver is stuck
140  if (!prev_waypoint_target_)
141  {
142  // Just initialize if this is the first iteration
143  prev_waypoint_target_ = robot_command.getFirstWayPointPtr();
144  }
145  else
146  {
147  if (prev_waypoint_target_->distance(*robot_command.getFirstWayPointPtr()) <= STUCK_THRESHOLD_RAD)
148  {
149  ++num_iterations_stuck_;
150  if (num_iterations_stuck_ > STUCK_ITERATIONS_THRESHOLD)
151  {
152  num_iterations_stuck_ = 0;
153  prev_waypoint_target_ = nullptr;
154  feedback_result.feedback = toString(LocalFeedbackEnum::LOCAL_PLANNER_STUCK);
155  path_invalidation_event_send_ = true; // Set feedback flag
156  RCLCPP_INFO(LOGGER, "The local planner has been stuck for several iterations. Aborting.");
157  }
158  }
159  prev_waypoint_target_ = robot_command.getFirstWayPointPtr();
160  }
161  }
162 
163  // Transform robot trajectory into joint_trajectory message
164  moveit_msgs::msg::RobotTrajectory robot_command_msg;
165  robot_command.getRobotTrajectoryMsg(robot_command_msg);
166  local_solution = robot_command_msg.joint_trajectory;
167 
168  return feedback_result;
169 }
170 } // namespace moveit::hybrid_planning
171 
172 #include <pluginlib/class_list_macros.hpp>
173 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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...
Definition: robot_state.h:229
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:322
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
Definition: async_test.h:31