moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
40namespace
41{
42// If stuck for this many iterations or more, abort the local planning action
43constexpr size_t STUCK_ITERATIONS_THRESHOLD = 5;
44constexpr double STUCK_THRESHOLD_RAD = 1e-4; // L1-norm sum across all joints
45} // namespace
46
48{
49bool ForwardTrajectory::initialize(const rclcpp::Node::SharedPtr& node,
50 const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
51 const std::string& /* unused */)
52{
53 // Load parameter & initialize member variables
54 if (node->has_parameter("stop_before_collision"))
55 {
56 node->get_parameter<bool>("stop_before_collision", stop_before_collision_);
57 }
58 else
59 {
60 stop_before_collision_ = node->declare_parameter<bool>("stop_before_collision", false);
61 }
62 node_ = node;
63 path_invalidation_event_send_ = false;
64 num_iterations_stuck_ = 0;
65
66 planning_scene_monitor_ = planning_scene_monitor;
67
68 return true;
69}
70
72{
73 num_iterations_stuck_ = 0;
74 prev_waypoint_target_.reset();
75 path_invalidation_event_send_ = false;
76 return true;
77};
78
79moveit_msgs::action::LocalPlanner::Feedback
81 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> /* unused */,
82 trajectory_msgs::msg::JointTrajectory& local_solution)
83{
84 // A message every once in awhile is useful in case the local planner gets stuck
85#pragma GCC diagnostic push
86#pragma GCC diagnostic ignored "-Wold-style-cast"
87 RCLCPP_INFO_THROTTLE(node_->get_logger(), *node_->get_clock(), 2000 /* ms */, "The local planner is solving...");
88#pragma GCC diagnostic pop
89
90 // Create controller command trajectory
91 robot_trajectory::RobotTrajectory robot_command(local_trajectory.getRobotModel(), local_trajectory.getGroupName());
92
93 // Feedback
94 moveit_msgs::action::LocalPlanner::Feedback feedback_result;
95
96 // If this flag is set, ignore collisions
97 if (!stop_before_collision_)
98 {
99 robot_command.addSuffixWayPoint(local_trajectory.getWayPoint(0), 0.0);
100 }
101 else
102 {
103 // Get current planning scene
104 planning_scene_monitor_->updateFrameTransforms();
105
106 moveit::core::RobotStatePtr current_state;
107 bool is_path_valid = false;
108 // Lock the planning scene as briefly as possible
109 {
110 planning_scene_monitor_->updateSceneWithCurrentState();
111 planning_scene_monitor::LockedPlanningSceneRO locked_planning_scene(planning_scene_monitor_);
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);
114 }
115
116 // Check if path is valid
117 if (is_path_valid)
118 {
119 if (path_invalidation_event_send_)
120 {
121 path_invalidation_event_send_ = false; // Reset flag
122 }
123 // Forward next waypoint to the robot controller
124 robot_command.addSuffixWayPoint(local_trajectory.getWayPoint(0), 0.0);
125 }
126 else
127 {
128 if (!path_invalidation_event_send_)
129 { // Send feedback only once
130 feedback_result.feedback = toString(LocalFeedbackEnum::COLLISION_AHEAD);
131 path_invalidation_event_send_ = true; // Set feedback flag
132 }
133 RCLCPP_INFO(node_->get_logger(), "Collision ahead, holding current position");
134 // Keep current position
135 moveit::core::RobotState current_state_command(*current_state);
136 if (current_state_command.hasVelocities())
137 {
138 current_state_command.zeroVelocities();
139 }
140 if (current_state_command.hasAccelerations())
141 {
142 current_state_command.zeroAccelerations();
143 }
144 robot_command.empty();
145 robot_command.addSuffixWayPoint(*current_state, local_trajectory.getWayPointDurationFromPrevious(0));
146 }
147
148 // Detect if the local solver is stuck
149 if (!prev_waypoint_target_)
150 {
151 // Just initialize if this is the first iteration
152 prev_waypoint_target_ = robot_command.getFirstWayPointPtr();
153 }
154 else
155 {
156 if (prev_waypoint_target_->distance(*robot_command.getFirstWayPointPtr()) <= STUCK_THRESHOLD_RAD)
157 {
158 ++num_iterations_stuck_;
159 if (num_iterations_stuck_ > STUCK_ITERATIONS_THRESHOLD)
160 {
161 num_iterations_stuck_ = 0;
162 prev_waypoint_target_ = nullptr;
163 feedback_result.feedback = toString(LocalFeedbackEnum::LOCAL_PLANNER_STUCK);
164 path_invalidation_event_send_ = true; // Set feedback flag
165 RCLCPP_INFO(node_->get_logger(), "The local planner has been stuck for several iterations. Aborting.");
166 }
167 }
168 prev_waypoint_target_ = robot_command.getFirstWayPointPtr();
169 }
170 }
171
172 // Transform robot trajectory into joint_trajectory message
173 moveit_msgs::msg::RobotTrajectory robot_command_msg;
174 robot_command.getRobotTrajectoryMsg(robot_command_msg);
175 local_solution = robot_command_msg.joint_trajectory;
176
177 return feedback_result;
178}
179} // namespace moveit::hybrid_planning
180
181#include <pluginlib/class_list_macros.hpp>
182
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
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...
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
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
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
moveit::core::RobotStatePtr & getFirstWayPointPtr()
double getWayPointDurationFromPrevious(std::size_t index) const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
constexpr std::string_view toString(const LocalFeedbackEnum &code)