moveit2
The MoveIt Motion Planning Framework for ROS 2.
add_time_optimal_parameterization.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, 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 Willow Garage 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 
35 /* Author: Ioan Sucan, Michael Ferguson */
36 
39 #include <class_loader/class_loader.hpp>
40 #include <moveit/utils/logger.hpp>
41 
42 #include <default_plan_request_adapter_parameters.hpp>
43 
45 {
46 using namespace trajectory_processing;
47 
50 {
51 public:
52  AddTimeOptimalParameterization() : logger_(moveit::makeChildLogger("add_time_optimal_parameterization"))
53  {
54  }
55 
56  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
57  {
58  param_listener_ =
59  std::make_unique<default_plan_request_adapter_parameters::ParamListener>(node, parameter_namespace);
60  }
61 
62  std::string getDescription() const override
63  {
64  return "Add Time Optimal Parameterization";
65  }
66 
67  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
69  planning_interface::MotionPlanResponse& res) const override
70  {
71  bool result = planner(planning_scene, req, res);
72  if (result && res.trajectory)
73  {
74  RCLCPP_DEBUG(logger_, " Running '%s'", getDescription().c_str());
75  const auto params = param_listener_->get_params();
76  TimeOptimalTrajectoryGeneration totg(params.path_tolerance, params.resample_dt, params.min_angle_change);
77  if (!totg.computeTimeStamps(*res.trajectory, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor))
78  {
79  RCLCPP_WARN(logger_, " Time parametrization for the solution path failed.");
80  result = false;
81  }
82  }
83 
84  return result;
85  }
86 
87 protected:
88  std::unique_ptr<default_plan_request_adapter_parameters::ParamListener> param_listener_;
89  rclcpp::Logger logger_;
90 };
91 
92 } // namespace default_planner_request_adapters
93 
This adapter uses the time-optimal trajectory generation method.
std::string getDescription() const override
Get a description of this adapter.
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::unique_ptr< default_plan_request_adapter_parameters::ParamListener > param_listener_
Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-proc...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Functional interface to call a planning function.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Main namespace for MoveIt.
Definition: exceptions.h:43
rclcpp::Logger makeChildLogger(const std::string &name)
Definition: logger.cpp:93
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
Response to a planning query.
robot_trajectory::RobotTrajectoryPtr trajectory