35 #include <gtest/gtest.h> 
   87     container_.addLimit(
"joint1", lim1);
 
   88     container_.addLimit(
"joint2", lim2);
 
   89     container_.addLimit(
"joint3", lim3);
 
   90     container_.addLimit(
"joint4", lim4);
 
   91     container_.addLimit(
"joint5", lim5);
 
   92     container_.addLimit(
"joint6", lim6);
 
   94     common_limit_ = container_.getCommonLimit();
 
  106   EXPECT_EQ(-1, common_limit_.min_position);
 
  107   EXPECT_EQ(1, common_limit_.max_position);
 
  115   EXPECT_EQ(2, common_limit_.max_velocity);
 
  123   EXPECT_EQ(3, common_limit_.max_acceleration);
 
  131   EXPECT_EQ(-5, common_limit_.max_deceleration);
 
  153   EXPECT_EQ(
false, container.
addLimit(
"joint_invalid1", lim_invalid1));
 
  154   EXPECT_EQ(
false, container.
addLimit(
"joint_invalid2", lim_invalid2));
 
  155   EXPECT_EQ(
true, container.
addLimit(
"joint_valid", lim_valid));
 
  168   ASSERT_TRUE(container.
addLimit(
"joint_valid", lim_valid));
 
  169   EXPECT_FALSE(container.
addLimit(
"joint_valid", lim_valid));
 
  206 int main(
int argc, 
char** argv)
 
  208   testing::InitGoogleTest(&argc, argv);
 
  209   return RUN_ALL_TESTS();
 
pilz_industrial_motion_planner::JointLimitsContainer container_
 
pilz_industrial_motion_planner::JointLimit common_limit_
 
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
 
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
 
JointLimit getCommonLimit() const
Returns joint limit fusion of all(position, velocity, acceleration, deceleration) limits for all join...
 
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
 
bool has_acceleration_limits
 
Extends joint_limits_interface::JointLimits with a deceleration parameter.
 
bool has_deceleration_limits
 
double max_deceleration
maximum deceleration MUST(!) be negative
 
int main(int argc, char **argv)