35#include <gtest/gtest.h>
44#include <rclcpp/rclcpp.hpp>
54 rclcpp::NodeOptions node_options;
56 node_ = rclcpp::Node::make_shared(
"unittest_joint_limits_aggregator", node_options);
59 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(
node_);
61 ASSERT_TRUE(
bool(
robot_model_)) <<
"Failed to load robot model";
72 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
83 robot_model_->getActiveJointModels());
85 EXPECT_EQ(robot_model_->getActiveJointModels().size(), container.
getCount());
96 robot_model_->getActiveJointModels());
98 for (
const auto& lim : container)
101 if (lim.first ==
"prbt_joint_1")
109 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].min_position_,
111 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].max_position_,
125 robot_model_->getActiveJointModels());
127 for (
const auto& lim : container)
130 if (lim.first ==
"prbt_joint_3")
136 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].max_velocity_,
149 robot_model_->getActiveJointModels());
151 for (
const auto& lim : container)
153 if (lim.first ==
"prbt_joint_4")
158 else if (lim.first ==
"prbt_joint_5")
177 node_,
"violate_position_min", robot_model_->getActiveJointModels()),
181 node_,
"violate_position_max", robot_model_->getActiveJointModels()),
191 node_,
"violate_velocity", robot_model_->getActiveJointModels()),
197 rclcpp::init(argc, argv);
198 testing::InitGoogleTest(&argc, argv);
199 return RUN_ALL_TESTS();
Unittest of the JointLimitsAggregator class.
moveit::core::RobotModelConstPtr robot_model_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
rclcpp::Node::SharedPtr node_
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string ¶m_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
JointLimit getLimit(const std::string &joint_name) const
getLimit get the limit for the given joint name
size_t getCount() const
Get Number of limits in the container.
double max_deceleration
maximum deceleration MUST(!) be negative
TEST_F(JointLimitsAggregator, ExpectedMapSize)
Check for that the size of the map and the size of the given joint models is equal.
int main(int argc, char **argv)