limit_max_cartesian_link_speed.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * Copyright (c) 2020, Benjamin Scholz
6  * Copyright (c) 2021, Thies Oelerich
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the authors nor the names of other
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /* Authors: Benjamin Scholz, Thies Oelerich, based off add_time_parameterization.cpp by Ioan Sucan */
38 
42 #include <ros/console.h>
43 
45 {
46 class LimitMaxCartesianLinkSpeed : public planning_request_adapter::PlanningRequestAdapter
47 {
48 public:
50  {
51  }
52 
53  void initialize(const ros::NodeHandle& /*nh*/) override
54  {
55  }
56 
57  std::string getDescription() const override
58  {
59  return "Limiting Max Cartesian Speed";
60  }
61 
62  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
64  std::vector<std::size_t>& /*added_path_index*/) const override
65  {
66  bool result = planner(planning_scene, req, res);
67  if (result && res.trajectory_)
68  {
69  if (req.max_cartesian_speed <= 0.0)
70  return result;
71  ROS_DEBUG("'%s' below '%f' [m/s] for link '%s'", getDescription().c_str(), req.max_cartesian_speed,
72  req.cartesian_speed_limited_link.c_str());
73  if (!trajectory_processing::limitMaxCartesianLinkSpeed(*res.trajectory_, req.max_cartesian_speed,
74  req.cartesian_speed_limited_link))
75  {
76  ROS_ERROR("Limiting Cartesian speed for the solution path failed.");
77  result = false;
78  }
79  }
80  return result;
81  }
82 };
83 } // namespace default_planner_request_adapters
84 
default_planner_request_adapters::LimitMaxCartesianLinkSpeed::getDescription
std::string getDescription() const override
Definition: limit_max_cartesian_link_speed.cpp:125
planning_interface::MotionPlanResponse
limit_cartesian_speed.h
planning_request_adapter.h
ROS_DEBUG
#define ROS_DEBUG(...)
default_planner_request_adapters::LimitMaxCartesianLinkSpeed::initialize
void initialize(const ros::NodeHandle &) override
Definition: limit_max_cartesian_link_speed.cpp:121
planning_request_adapter::PlanningRequestAdapter
trajectory_processing::limitMaxCartesianLinkSpeed
bool limitMaxCartesianLinkSpeed(robot_trajectory::RobotTrajectory &trajectory, const double speed, const moveit::core::LinkModel *link_model)
console.h
default_planner_request_adapters::LimitMaxCartesianLinkSpeed::adaptAndPlan
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &) const override
Definition: limit_max_cartesian_link_speed.cpp:130
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
default_planner_request_adapters::LimitMaxCartesianLinkSpeed
Definition: limit_max_cartesian_link_speed.cpp:80
ROS_ERROR
#define ROS_ERROR(...)
class_loader.hpp
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter
PlanningRequestAdapter()
default_planner_request_adapters
Definition: add_iterative_spline_parameterization.cpp:43
planning_request_adapter::PlanningRequestAdapter::PlannerFn
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
planning_request_adapter
planning_scene
default_planner_request_adapters::LimitMaxCartesianLinkSpeed::LimitMaxCartesianLinkSpeed
LimitMaxCartesianLinkSpeed()
Definition: limit_max_cartesian_link_speed.cpp:117
ros::NodeHandle


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03