moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_cartesian_limits_aggregator.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 #include <gtest/gtest.h>
36 
37 #include <rclcpp/rclcpp.hpp>
38 
41 
45 class CartesianLimitsAggregator : public ::testing::Test
46 {
47 protected:
48  void SetUp() override
49  {
50  node_ = rclcpp::Node::make_shared("unittest_cartesian_limits_aggregator");
51  }
52  rclcpp::Node::SharedPtr node_;
53 };
54 
59 {
62  EXPECT_TRUE(limit.hasMaxTranslationalVelocity());
63  EXPECT_EQ(limit.getMaxTranslationalVelocity(), 10);
64  EXPECT_FALSE(limit.hasMaxTranslationalAcceleration());
65  EXPECT_FALSE(limit.hasMaxTranslationalDeceleration());
66  EXPECT_FALSE(limit.hasMaxRotationalVelocity());
67 }
68 
73 {
76  EXPECT_TRUE(limit.hasMaxTranslationalVelocity());
77  EXPECT_EQ(limit.getMaxTranslationalVelocity(), 1);
78 
79  EXPECT_TRUE(limit.hasMaxTranslationalAcceleration());
80  EXPECT_EQ(limit.getMaxTranslationalAcceleration(), 2);
81 
82  EXPECT_TRUE(limit.hasMaxTranslationalDeceleration());
83  EXPECT_EQ(limit.getMaxTranslationalDeceleration(), -3);
84 
85  EXPECT_TRUE(limit.hasMaxRotationalVelocity());
86  EXPECT_EQ(limit.getMaxRotationalVelocity(), 4);
87 }
88 
89 int main(int argc, char** argv)
90 {
91  rclcpp::init(argc, argv);
92  testing::InitGoogleTest(&argc, argv);
93  return RUN_ALL_TESTS();
94 }
Unittest of the CartesianLimitsAggregator class.
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
double getMaxRotationalVelocity() const
Return the maximal rotational velocity [rad/s], 0 if nothing was set.
bool hasMaxRotationalVelocity() const
Check if rotational velocity limit is set.
bool hasMaxTranslationalDeceleration() const
Check if translational deceleration limit is set.
double getMaxTranslationalDeceleration() const
Return the maximal translational deceleration [m/s^2], 0 if nothing was set.
bool hasMaxTranslationalVelocity() const
Check if translational velocity limit is set.
double getMaxTranslationalAcceleration() const
Return the maximal translational acceleration [m/s^2], 0 if nothing was set.
double getMaxTranslationalVelocity() const
Return the maximal translational velocity [m/s], 0 if nothing was set.
bool hasMaxTranslationalAcceleration() const
Check if translational acceleration limit is set.
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace)
Loads cartesian limits from the node parameters.
int main(int argc, char **argv)
TEST_F(CartesianLimitsAggregator, OnlyVelocity)
Check if only velocity is set.