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 
26 class JointLimitTest : public ::testing::Test
27 {
28 };
29 
33 TEST_F(JointLimitTest, SimpleRead) {
34  ros::NodeHandle node_handle("~");
35 
36  // Joints limits interface
39 
40  pilz_extensions::joint_limits_interface::getJointLimits("joint_1", node_handle, joint_limits_extended);
41 
42  EXPECT_EQ(1, joint_limits_extended.max_acceleration);
43  EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
44 }
45 
50  ros::NodeHandle node_handle("~");
51 
52  // Joints limits interface
54  joint_limits_interface::getJointLimits("joint_1", node_handle, joint_limits);
55 
56  EXPECT_EQ(1, joint_limits.max_acceleration);
57 }
58 
59 int main(int argc, char **argv)
60 {
61  ros::init(argc, argv, "unittest_joint_limits_extended");
62  testing::InitGoogleTest(&argc, argv);
63  return RUN_ALL_TESTS();
64 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double max_deceleration
maximum deceleration MUST(!) be negative
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh,::pilz_extensions::joint_limits_interface::JointLimits &limits)
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
Extends joint_limits_interface::JointLimits with a deceleration parameter.
int main(int argc, char **argv)
TEST_F(JointLimitTest, SimpleRead)
Simple read.


pilz_extensions
Author(s):
autogenerated on Mon Apr 6 2020 03:17:24