unittest_joint_limit.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Pilz GmbH & Co. KG
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include "ros/ros.h"
18 
19 #include <gtest/gtest.h>
20 
21 #include <moveit_msgs/MoveItErrorCodes.h>
22 
25 
27 {
28 
29 class JointLimitTest : public ::testing::Test
30 {
31 };
32 
33 TEST_F(JointLimitTest, SimpleRead)
34 {
35  ros::NodeHandle node_handle("~");
36 
37  // Joints limits interface
40 
41  pilz_extensions::joint_limits_interface::getJointLimits("joint_1", node_handle, joint_limits_extended);
42 
43  EXPECT_EQ(1, joint_limits_extended.max_acceleration);
44  EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
45 }
46 
47 TEST_F(JointLimitTest, readNonExistingJointLimit)
48 {
49  ros::NodeHandle node_handle("~");
50 
51  // Joints limits interface
54 
56  node_handle,
57  joint_limits_extended));
58 }
59 
65 TEST_F(JointLimitTest, readInvalidParameterName)
66 {
67  ros::NodeHandle node_handle("~");
68 
69  // Joints limits interface
72 
74  node_handle,
75  joint_limits_extended));
76 }
77 
79 {
80  ros::NodeHandle node_handle("~");
81 
82  // Joints limits interface
84  joint_limits_interface::getJointLimits("joint_1", node_handle, joint_limits);
85 
86  EXPECT_EQ(1, joint_limits.max_acceleration);
87 }
88 
89 } // namespace pilz_extensions_tests
90 
91 int main(int argc, char **argv)
92 {
93  ros::init(argc, argv, "unittest_joint_limits_extended");
94  testing::InitGoogleTest(&argc, argv);
95  return RUN_ALL_TESTS();
96 }
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, ::pilz_extensions::joint_limits_interface::JointLimits &limits)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(JointLimitTest, SimpleRead)
double max_deceleration
maximum deceleration MUST(!) be negative
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
Extends joint_limits_interface::JointLimits with a deceleration parameter.
int main(int argc, char **argv)


pilz_extensions
Author(s):
autogenerated on Mon Feb 28 2022 23:13:29