moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_calcs_unit_tests.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 
35 /* Author: Tyler Weaver, Andy Zelenak
36  Desc: Unit tests
37 */
38 
39 #include <gtest/gtest.h>
40 
42 
47 #include <moveit_servo/utilities.h>
48 
49 namespace
50 {
51 constexpr double PUBLISH_PERIOD = 0.01;
52 
53 void checkVelocityLimits(const moveit::core::JointModelGroup* joint_model_group, const Eigen::ArrayXd& velocity)
54 {
55  std::size_t joint_index{ 0 };
56  for (const moveit::core::JointModel* joint : joint_model_group->getActiveJointModels())
57  {
58  const auto& bounds = joint->getVariableBounds(joint->getName());
59 
60  if (bounds.velocity_bounded_)
61  {
62  EXPECT_GE(velocity(joint_index), bounds.min_velocity_) << "Joint " << joint_index << " violates velocity limit";
63  EXPECT_LE(velocity(joint_index), bounds.max_velocity_) << "Joint " << joint_index << " violates velocity limit";
64  }
65  ++joint_index;
66  }
67 }
68 
69 class ServoCalcsUnitTests : public testing::Test
70 {
71 protected:
72  void SetUp() override
73  {
74  robot_model_ = moveit::core::loadTestingRobotModel("panda");
75  joint_model_group_ = robot_model_->getJointModelGroup("panda_arm");
76  }
77 
78  moveit::core::RobotModelPtr robot_model_;
79  const moveit::core::JointModelGroup* joint_model_group_;
80 };
81 
82 } // namespace
83 
84 TEST_F(ServoCalcsUnitTests, VelocitiesTooFast)
85 {
86  // Request velocities that are too fast
87  std::vector<double> joint_position{ 0, 0, 0, 0, 0, 0, 0 };
88  std::vector<double> joint_velocity{ 0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0 };
89  sensor_msgs::msg::JointState joint_state;
90  joint_state.position = joint_position;
91  joint_state.velocity = joint_velocity;
92 
93  moveit_servo::enforceVelocityLimits(joint_model_group_, PUBLISH_PERIOD, joint_state);
94 
95  Eigen::ArrayXd eigen_velocity =
96  Eigen::Map<Eigen::ArrayXd, Eigen::Unaligned>(joint_state.velocity.data(), joint_state.velocity.size());
97  checkVelocityLimits(joint_model_group_, eigen_velocity);
98 }
99 
100 TEST_F(ServoCalcsUnitTests, NegativeVelocitiesTooFast)
101 {
102  // Negative velocities exceeding the limit
103  std::vector<double> joint_position{ 0, 0, 0, 0, 0, 0, 0 };
104  std::vector<double> joint_velocity{ 0, -1.0, -2.0, -3.0, -4.0, -5.0, -6.0 };
105  sensor_msgs::msg::JointState joint_state;
106  joint_state.position = joint_position;
107  joint_state.velocity = joint_velocity;
108 
109  moveit_servo::enforceVelocityLimits(joint_model_group_, PUBLISH_PERIOD, joint_state);
110 
111  Eigen::ArrayXd eigen_velocity =
112  Eigen::Map<Eigen::ArrayXd, Eigen::Unaligned>(joint_state.velocity.data(), joint_state.velocity.size());
113  checkVelocityLimits(joint_model_group_, eigen_velocity);
114 }
115 
116 TEST_F(ServoCalcsUnitTests, AcceptableJointVelocities)
117 {
118  // Final test with joint velocities that are acceptable
119  std::vector<double> joint_position{ 0, 0, 0, 0, 0, 0, 0 };
120  std::vector<double> joint_velocity{ 0, 0.001, 0.001, -0.001, 0.001, 0.001, 0.001 };
121  sensor_msgs::msg::JointState joint_state;
122  joint_state.position = joint_position;
123  joint_state.velocity = joint_velocity;
124 
125  moveit_servo::enforceVelocityLimits(joint_model_group_, PUBLISH_PERIOD, joint_state);
126 
127  Eigen::ArrayXd eigen_velocity =
128  Eigen::Map<Eigen::ArrayXd, Eigen::Unaligned>(joint_state.velocity.data(), joint_state.velocity.size());
129  checkVelocityLimits(joint_model_group_, eigen_velocity);
130 }
131 
132 TEST_F(ServoCalcsUnitTests, SingularityScaling)
133 {
134  // If we are at a singularity, we should halt
135  Eigen::VectorXd commanded_twist(6);
136  commanded_twist << 1, 0, 0, 0, 0, 0;
137 
138  // Start near a singularity
139  std::shared_ptr<moveit::core::RobotState> robot_state = std::make_shared<moveit::core::RobotState>(robot_model_);
140  robot_state->setToDefaultValues();
141  robot_state->setVariablePosition("panda_joint1", 0.221);
142  robot_state->setVariablePosition("panda_joint2", 0.530);
143  robot_state->setVariablePosition("panda_joint3", -0.231);
144  robot_state->setVariablePosition("panda_joint4", -0.920);
145  robot_state->setVariablePosition("panda_joint5", 0.117);
146  robot_state->setVariablePosition("panda_joint6", 1.439);
147  robot_state->setVariablePosition("panda_joint7", -1.286);
148 
149  Eigen::MatrixXd jacobian = robot_state->getJacobian(joint_model_group_);
150 
151  Eigen::JacobiSVD<Eigen::MatrixXd> svd =
152  Eigen::JacobiSVD<Eigen::MatrixXd>(jacobian, Eigen::ComputeThinU | Eigen::ComputeThinV);
153  Eigen::MatrixXd matrix_s = svd.singularValues().asDiagonal();
154  Eigen::MatrixXd pseudo_inverse = svd.matrixV() * matrix_s.inverse() * svd.matrixU().transpose();
155 
156  // Use very low thresholds to ensure they are triggered
157  double hard_stop_singularity_threshold = 2;
158  double lower_singularity_threshold = 1;
159  double leaving_singularity_threshold_multiplier = 2;
160 
161  rclcpp::Clock clock;
163 
165  joint_model_group_, commanded_twist, svd, pseudo_inverse, hard_stop_singularity_threshold,
166  lower_singularity_threshold, leaving_singularity_threshold_multiplier, clock, robot_state, status);
167 
168  EXPECT_EQ(scaling_factor, 0);
169 }
170 
171 int main(int argc, char** argv)
172 {
173  rclcpp::init(argc, argv);
174  ::testing::InitGoogleTest(&argc, argv);
175  int result = RUN_ALL_TESTS();
176  rclcpp::shutdown();
177  return result;
178 }
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
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
double velocityScalingFactorForSingularity(const moveit::core::JointModelGroup *joint_model_group, const Eigen::VectorXd &commanded_twist, const Eigen::JacobiSVD< Eigen::MatrixXd > &svd, const Eigen::MatrixXd &pseudo_inverse, const double hard_stop_singularity_threshold, const double lower_singularity_threshold, const double leaving_singularity_threshold_multiplier, rclcpp::Clock &clock, moveit::core::RobotStatePtr &current_state, StatusCode &status)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
Definition: utilities.cpp:88
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.
TEST_F(ServoCalcsUnitTests, VelocitiesTooFast)
int main(int argc, char **argv)