moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_utils.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, 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 : V Mohammed Ibrahim
36  Desc : Tests for utilities that depend on the robot/ robot state.
37  Title : test_utils.cpp
38  Project : moveit_servo
39  Created : 06/20/2023
40 */
41 
42 #include <gtest/gtest.h>
43 #include <moveit_servo/servo.hpp>
47 #include <tf2_eigen/tf2_eigen.hpp>
48 
49 namespace
50 {
51 
52 TEST(ServoUtilsUnitTests, JointLimitVelocityScaling)
53 {
55  moveit::core::RobotModelPtr robot_model = loadTestingRobotModel("panda");
56  const auto joint_model_group = robot_model->getJointModelGroup("panda_arm");
57  const auto joint_bounds = joint_model_group->getActiveJointModelsBounds();
58 
59  // Get the upper bound for the velocities of each joint.
60  Eigen::VectorXd incoming_velocities(joint_bounds.size());
61  for (size_t i = 0; i < joint_bounds.size(); ++i)
62  {
63  const auto joint_bound = (*joint_bounds[i])[0];
64  if (joint_bound.velocity_bounded_)
65  {
66  incoming_velocities(i) = joint_bound.max_velocity_;
67  }
68  }
69 
70  // Create incoming velocities with only joint 1 and joint 2 over limit by a factor of 0.1 and 0.05
71  // Scale down all other joint velocities by 0.3 to keep it within limits.
72  incoming_velocities(0) *= 1.1;
73  incoming_velocities(1) *= 1.05;
74  incoming_velocities.tail<5>() *= 0.7;
75 
76  constexpr double tol = 0.001;
77 
78  // The resulting scaling factor from joints should be 1 / 1.1 = 0.90909
79  double user_velocity_override = 0.0;
80  double scaling_factor =
81  moveit_servo::jointLimitVelocityScalingFactor(incoming_velocities, joint_bounds, user_velocity_override);
82  ASSERT_NEAR(scaling_factor, 1.0 / 1.1, tol);
83 
84  // With a scaling override lower than the joint limit scaling, it should use the override value.
85  user_velocity_override = 0.5;
86  scaling_factor =
87  moveit_servo::jointLimitVelocityScalingFactor(incoming_velocities, joint_bounds, user_velocity_override);
88  ASSERT_NEAR(scaling_factor, 0.5, tol);
89 
90  // With a scaling override higher than the joint limit scaling, it should still use the joint limits.
91  // Safety always first!
92  user_velocity_override = 1.0;
93  scaling_factor =
94  moveit_servo::jointLimitVelocityScalingFactor(incoming_velocities, joint_bounds, user_velocity_override);
95  ASSERT_NEAR(scaling_factor, 1.0 / 1.1, tol);
96 }
97 
98 TEST(ServoUtilsUnitTests, validVector)
99 {
100  Eigen::VectorXd valid_vector(7);
101  valid_vector << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0;
102  EXPECT_TRUE(moveit_servo::isValidCommand(valid_vector));
103 }
104 
105 TEST(ServoUtilsUnitTests, invalidVector)
106 {
107  Eigen::VectorXd invalid_vector(6);
108  invalid_vector << 0.0, 0.0, 0.0, 0.0, std::nan(""), 0.0;
109  EXPECT_FALSE(moveit_servo::isValidCommand(invalid_vector));
110 }
111 
112 TEST(ServoUtilsUnitTests, validTwist)
113 {
114  Eigen::VectorXd valid_vector(6);
115  valid_vector << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0;
116  moveit_servo::TwistCommand valid_twist{ "panda_link0", valid_vector };
117  EXPECT_TRUE(moveit_servo::isValidCommand(valid_twist));
118 }
119 
120 TEST(ServoUtilsUnitTests, emptyTwistFrame)
121 {
122  Eigen::VectorXd invalid_vector(6);
123  invalid_vector << 0.0, 0.0, 0.0, 0.0, std::nan(""), 0.0;
124  moveit_servo::TwistCommand invalid_twist;
125  invalid_twist.velocities = invalid_vector;
126  EXPECT_FALSE(moveit_servo::isValidCommand(invalid_twist));
127 }
128 
129 TEST(ServoUtilsUnitTests, invalidTwistVelocities)
130 {
131  Eigen::VectorXd invalid_vector(6);
132  invalid_vector << 0.0, 0.0, 0.0, 0.0, 0.0, std::nan("");
133  moveit_servo::TwistCommand invalid_twist{ "panda_link0", invalid_vector };
134  EXPECT_FALSE(moveit_servo::isValidCommand(invalid_twist));
135 }
136 
137 TEST(ServoUtilsUnitTests, validIsometry)
138 {
139  Eigen::Isometry3d valid_isometry;
140  valid_isometry.setIdentity();
141  EXPECT_TRUE(moveit_servo::isValidCommand(valid_isometry));
142 }
143 
144 TEST(ServoUtilsUnitTests, invalidIsometry)
145 {
146  Eigen::Isometry3d invalid_isometry;
147  invalid_isometry.setIdentity();
148  invalid_isometry.translation().z() = std::nan("");
149  EXPECT_FALSE(moveit_servo::isValidCommand(invalid_isometry));
150 }
151 
152 TEST(ServoUtilsUnitTests, validPose)
153 {
154  Eigen::Isometry3d valid_isometry;
155  valid_isometry.setIdentity();
156  moveit_servo::PoseCommand valid_pose{ "panda_link0", valid_isometry };
157  EXPECT_TRUE(moveit_servo::isValidCommand(valid_pose));
158 }
159 
160 TEST(ServoUtilsUnitTests, ApproachingSingularityScaling)
161 {
163  moveit::core::RobotModelPtr robot_model = loadTestingRobotModel("panda");
164  moveit::core::RobotStatePtr robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
165 
166  servo::Params servo_params;
167  servo_params.move_group_name = "panda_arm";
168  const auto joint_model_group = robot_state->getJointModelGroup(servo_params.move_group_name);
169  robot_state->setToDefaultValues();
170 
171  Eigen::Vector<double, 6> cartesian_delta{ 0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };
172  // Home state
173  Eigen::Vector<double, 7> state_ready{ 0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785 };
174  robot_state->setJointGroupActivePositions(joint_model_group, state_ready);
175  auto scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
176  ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::NO_WARNING);
177 
178  // Approach singularity
179  Eigen::Vector<double, 7> state_approaching_singularity{ 0.0, 0.334, 0.0, -1.177, 0.0, 1.510, 0.785 };
180  robot_state->setJointGroupActivePositions(joint_model_group, state_approaching_singularity);
181  scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
183 }
184 
185 TEST(ServoUtilsUnitTests, HaltForSingularityScaling)
186 {
188  moveit::core::RobotModelPtr robot_model = loadTestingRobotModel("panda");
189  moveit::core::RobotStatePtr robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
190 
191  servo::Params servo_params;
192  servo_params.move_group_name = "panda_arm";
193  const auto joint_model_group = robot_state->getJointModelGroup(servo_params.move_group_name);
194  robot_state->setToDefaultValues();
195 
196  Eigen::Vector<double, 6> cartesian_delta{ 0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };
197 
198  // Home state
199  Eigen::Vector<double, 7> state_ready{ 0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785 };
200  robot_state->setJointGroupActivePositions(joint_model_group, state_ready);
201  auto scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
202  ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::NO_WARNING);
203 
204  // Move to singular state.
205  Eigen::Vector<double, 7> singular_state{ -0.0001, 0.5690, 0.0005, -0.7782, 0.0, 1.3453, 0.7845 };
206  robot_state->setJointGroupActivePositions(joint_model_group, singular_state);
207  scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
208  ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::HALT_FOR_SINGULARITY);
209 }
210 
211 TEST(ServoUtilsUnitTests, LeavingSingularityScaling)
212 {
214  moveit::core::RobotModelPtr robot_model = loadTestingRobotModel("panda");
215  moveit::core::RobotStatePtr robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
216 
217  servo::Params servo_params;
218  servo_params.move_group_name = "panda_arm";
219  const auto joint_model_group = robot_state->getJointModelGroup(servo_params.move_group_name);
220  robot_state->setToDefaultValues();
221 
222  Eigen::Vector<double, 6> cartesian_delta{ -0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };
223 
224  // Home state
225  Eigen::Vector<double, 7> state_ready{ 0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785 };
226  robot_state->setJointGroupActivePositions(joint_model_group, state_ready);
227  auto scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
228  ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::NO_WARNING);
229 
230  // Move away from singularity
231  Eigen::Vector<double, 7> state_leaving_singularity{ 0.0, 0.3458, 0.0, -1.1424, 0.0, 1.4865, 0.785 };
232  robot_state->setJointGroupActivePositions(joint_model_group, state_leaving_singularity);
233  scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
234  ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY);
235 }
236 
237 TEST(ServoUtilsUnitTests, ExtractRobotState)
238 {
240  moveit::core::RobotModelPtr robot_model = loadTestingRobotModel("panda");
241  moveit::core::RobotStatePtr robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
242  std::string joint_model_group = "panda_arm";
243  moveit_servo::KinematicState current_state;
244  current_state.positions = Eigen::VectorXd::Ones(7);
245  robot_state->setJointGroupPositions(joint_model_group, current_state.positions);
246  auto new_state = moveit_servo::extractRobotState(robot_state, joint_model_group);
247 
248  ASSERT_EQ(current_state.positions, new_state.positions);
249 }
250 
251 TEST(ServoUtilsUnitTests, SlidingWinodw)
252 {
253  double latency = .3;
254  moveit_servo::KinematicState current_state;
255  current_state.positions = Eigen::VectorXd::Ones(7);
256  current_state.joint_names = { "j1", "j2", "j3", "j4", "j5", "j6", "j7" };
257  std::deque<moveit_servo::KinematicState> window;
258  for (size_t i = 0; i < 10; ++i)
259  {
260  moveit_servo::updateSlidingWindow(current_state, window, latency, rclcpp::Time(100, i * 1E8, RCL_ROS_TIME));
261  }
262  // Add command at end of window with same timestamp. This should replace the command instead of adding it
263  moveit_servo::updateSlidingWindow(current_state, window, latency, rclcpp::Time(100, 9 * 1E8, RCL_ROS_TIME));
264 
265  ASSERT_EQ(window.size(), 7ul);
266  servo::Params params;
267  auto msg = moveit_servo::composeTrajectoryMessage(params, window);
268  ASSERT_TRUE(msg.has_value());
269  ASSERT_EQ(msg.value().points.size(), 6ul);
270 
271  // remove all but MIN_POINTS_FOR_TRAJ_MSG - 1 points
272  constexpr int min_points_for_traj_msg = 3;
273  while (window.size() > min_points_for_traj_msg - 1)
274  {
275  window.pop_front();
276  }
277  // ensure message is empty
278  msg = moveit_servo::composeTrajectoryMessage(params, window);
279  ASSERT_FALSE(msg.has_value());
280 }
281 
282 } // namespace
283 
284 int main(int argc, char** argv)
285 {
286  rclcpp::init(argc, argv);
287  ::testing::InitGoogleTest(&argc, argv);
288  int result = RUN_ALL_TESTS();
289  rclcpp::shutdown();
290  return result;
291 }
int main(int argc, char **argv)
Definition: test_utils.cpp:284
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
std::optional< trajectory_msgs::msg::JointTrajectory > composeTrajectoryMessage(const servo::Params &servo_params, const std::deque< KinematicState > &joint_cmd_rolling_window)
Create a trajectory message from a rolling window queue of joint state commands. Method optionally re...
Definition: common.cpp:151
std::pair< double, StatusCode > velocityScalingFactorForSingularity(const moveit::core::RobotStatePtr &robot_state, const Eigen::VectorXd &target_delta_x, const servo::Params &servo_params)
Computes scaling factor for velocity when the robot is near a singularity.
Definition: common.cpp:282
double jointLimitVelocityScalingFactor(const Eigen::VectorXd &velocities, const moveit::core::JointBoundsVector &joint_bounds, double scaling_override)
Apply velocity scaling based on joint limits. If the robot model does not have velocity limits define...
Definition: common.cpp:380
bool isValidCommand(const Eigen::VectorXd &command)
Checks if a given VectorXd is a valid command.
Definition: common.cpp:87
void updateSlidingWindow(KinematicState &next_joint_state, std::deque< KinematicState > &joint_cmd_rolling_window, double max_expected_latency, const rclcpp::Time &cur_time)
Adds a new joint state command to a queue containing commands over a time window. Also modifies the v...
Definition: common.cpp:203
KinematicState extractRobotState(const moveit::core::RobotStatePtr &robot_state, const std::string &move_group_name)
Extract the state from a RobotStatePtr instance.
Definition: common.cpp:516
std::vector< std::string > joint_names
Definition: datatypes.hpp:116
Eigen::Vector< double, 6 > velocities
Definition: datatypes.hpp:99
TEST(AllValid, Instantiate)