moveit2
The MoveIt Motion Planning Framework for ROS 2.
enforce_limits.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, LLC
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Title : enforce_limits.cpp
35  * Project : moveit_servo
36  * Created : 7/5/2021
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, Tyler Weaver
38  */
39 
40 #include <Eigen/Core>
41 #include <sensor_msgs/msg/joint_state.hpp>
42 
45 
46 namespace moveit_servo
47 {
48 namespace
49 {
50 double getVelocityScalingFactor(const moveit::core::JointModelGroup* joint_model_group, const Eigen::VectorXd& velocity)
51 {
52  std::size_t joint_delta_index{ 0 };
53  double velocity_scaling_factor{ 1.0 };
54  for (const moveit::core::JointModel* joint : joint_model_group->getActiveJointModels())
55  {
56  const auto& bounds = joint->getVariableBounds(joint->getName());
57  if (bounds.velocity_bounded_ && velocity(joint_delta_index) != 0.0)
58  {
59  const double unbounded_velocity = velocity(joint_delta_index);
60  // Clamp each joint velocity to a joint specific [min_velocity, max_velocity] range.
61  const auto bounded_velocity = std::min(std::max(unbounded_velocity, bounds.min_velocity_), bounds.max_velocity_);
62  velocity_scaling_factor = std::min(velocity_scaling_factor, bounded_velocity / unbounded_velocity);
63  }
64  ++joint_delta_index;
65  }
66 
67  return velocity_scaling_factor;
68 }
69 
70 } // namespace
71 
72 void enforceVelocityLimits(const moveit::core::JointModelGroup* joint_model_group, const double publish_period,
73  sensor_msgs::msg::JointState& joint_state, const double override_velocity_scaling_factor)
74 {
75  // Get the velocity scaling factor
76  Eigen::VectorXd velocity =
77  Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(joint_state.velocity.data(), joint_state.velocity.size());
78  double velocity_scaling_factor = override_velocity_scaling_factor;
79  // if the override velocity scaling factor is approximately zero then the user is not overriding the value.
80  if (override_velocity_scaling_factor < 0.01)
81  velocity_scaling_factor = getVelocityScalingFactor(joint_model_group, velocity);
82 
83  // Take a smaller step if the velocity scaling factor is less than 1
84  if (velocity_scaling_factor < 1)
85  {
86  Eigen::VectorXd velocity_residuals = (1 - velocity_scaling_factor) * velocity;
87  Eigen::VectorXd positions =
88  Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(joint_state.position.data(), joint_state.position.size());
89  positions -= velocity_residuals * publish_period;
90 
91  velocity *= velocity_scaling_factor;
92  // Back to sensor_msgs type
93  joint_state.velocity = std::vector<double>(velocity.data(), velocity.data() + velocity.size());
94  joint_state.position = std::vector<double>(positions.data(), positions.data() + positions.size());
95  }
96 }
97 
98 } // namespace moveit_servo
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
void enforceVelocityLimits(const moveit::core::JointModelGroup *joint_model_group, const double publish_period, sensor_msgs::msg::JointState &joint_state, const double override_velocity_scaling_factor=0.0)
Decrease robot position change and velocity, if needed, to satisfy joint velocity limits.