moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
41
42#include <default_response_adapter_parameters.hpp>
43
45{
46using namespace trajectory_processing;
47
50{
51public:
52 AddTimeOptimalParameterization() : logger_(moveit::getLogger("moveit.ros.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_ = std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
59 }
60
61 [[nodiscard]] std::string getDescription() const override
62 {
63 return std::string("AddTimeOptimalParameterization");
64 }
65
66 void adapt(const planning_scene::PlanningSceneConstPtr& /*planning_scene*/,
69 {
70 RCLCPP_DEBUG(logger_, " Running '%s'", getDescription().c_str());
71 if (!res.trajectory)
72 {
73 RCLCPP_ERROR(logger_, "Cannot apply response adapter '%s' because MotionPlanResponse does not contain a path.",
74 getDescription().c_str());
75 res.error_code = moveit::core::MoveItErrorCode::INVALID_MOTION_PLAN;
76 return;
77 }
78
79 const auto params = param_listener_->get_params().totg;
80 TimeOptimalTrajectoryGeneration totg(params.path_tolerance, params.resample_dt, params.min_angle_change);
81 if (totg.computeTimeStamps(*res.trajectory, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor))
82 {
83 res.error_code = moveit::core::MoveItErrorCode::SUCCESS;
84 }
85 else
86 {
87 RCLCPP_ERROR(logger_, "Response adapter '%s' failed to generate a trajectory.", getDescription().c_str());
88 res.error_code = moveit::core::MoveItErrorCode::FAILURE;
89 }
90 }
91
92protected:
93 std::unique_ptr<default_response_adapter_parameters::ParamListener> param_listener_;
94 rclcpp::Logger logger_;
95};
96
97} // namespace default_planning_response_adapters
98
This adapter uses the time-optimal trajectory generation method.
void adapt(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning response.
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.
std::unique_ptr< default_response_adapter_parameters::ParamListener > param_listener_
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning p...
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
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory