39 #include <gtest/gtest.h>
51 constexpr
double PUBLISH_PERIOD = 0.01;
55 std::size_t joint_index{ 0 };
58 const auto& bounds = joint->getVariableBounds(joint->getName());
60 if (bounds.velocity_bounded_)
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";
69 class ServoCalcsUnitTests :
public testing::Test
75 joint_model_group_ = robot_model_->getJointModelGroup(
"panda_arm");
78 moveit::core::RobotModelPtr robot_model_;
84 TEST_F(ServoCalcsUnitTests, VelocitiesTooFast)
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;
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);
100 TEST_F(ServoCalcsUnitTests, NegativeVelocitiesTooFast)
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;
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);
116 TEST_F(ServoCalcsUnitTests, AcceptableJointVelocities)
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;
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);
132 TEST_F(ServoCalcsUnitTests, SingularityScaling)
135 Eigen::VectorXd commanded_twist(6);
136 commanded_twist << 1, 0, 0, 0, 0, 0;
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);
149 Eigen::MatrixXd jacobian = robot_state->getJacobian(joint_model_group_);
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();
157 double hard_stop_singularity_threshold = 2;
158 double lower_singularity_threshold = 1;
159 double leaving_singularity_threshold_multiplier = 2;
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);
168 EXPECT_EQ(scaling_factor, 0);
171 int main(
int argc,
char** argv)
173 rclcpp::init(argc, argv);
174 ::testing::InitGoogleTest(&argc, argv);
175 int result = RUN_ALL_TESTS();
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....
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 ¤t_state, StatusCode &status)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
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)