35 #include <gtest/gtest.h>
37 #include <rclcpp/rclcpp.hpp>
50 node_ = rclcpp::Node::make_shared(
"unittest_cartesian_limits_aggregator");
89 int main(
int argc,
char** argv)
91 rclcpp::init(argc, argv);
92 testing::InitGoogleTest(&argc, argv);
93 return RUN_ALL_TESTS();
Unittest of the CartesianLimitsAggregator class.
rclcpp::Node::SharedPtr node_
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 ¶m_namespace)
Loads cartesian limits from the node parameters.
int main(int argc, char **argv)
TEST_F(CartesianLimitsAggregator, OnlyVelocity)
Check if only velocity is set.