35 #include <rclcpp/rclcpp.hpp> 
   37 #include <gtest/gtest.h> 
   52     node_ = rclcpp::Node::make_shared(
"unittest_joint_limits_extended");
 
   63   EXPECT_TRUE(
getJointLimits(
"joint_1", 
"", node_, joint_limits_extended));
 
   74   EXPECT_FALSE(
getJointLimits(
"anything", 
"", node_, joint_limits_extended));
 
   87   EXPECT_FALSE(
getJointLimits(
"~anything", 
"", node_, joint_limits_extended));
 
  102 int main(
int argc, 
char** argv)
 
  104   rclcpp::init(argc, argv);
 
  105   testing::InitGoogleTest(&argc, argv);
 
  106   return RUN_ALL_TESTS();
 
rclcpp::Node::SharedPtr node_
 
bool getJointLimits(const std::string &joint_name, const std::string ¶m_ns, const rclcpp::Node::SharedPtr &node, joint_limits_interface::JointLimits &limits)
 
bool declareParameters(const std::string &joint_name, const std::string ¶m_ns, const rclcpp::Node::SharedPtr &node)
 
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
 
Extends joint_limits_interface::JointLimits with a deceleration parameter.
 
double max_deceleration
maximum deceleration MUST(!) be negative
 
int main(int argc, char **argv)