36 #include <gtest/gtest.h>
43 constexpr
double DEFAULT_TIMESTEP = 0.1;
44 constexpr
char JOINT_GROUP[] =
"panda_arm";
46 class RuckigTests :
public testing::Test
52 trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, JOINT_GROUP);
55 moveit::core::RobotModelPtr robot_model_;
56 robot_trajectory::RobotTrajectoryPtr trajectory_;
62 TEST_F(RuckigTests, basic_trajectory)
67 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
70 std::vector<double> joint_positions;
72 joint_positions.at(0) += 0.05;
75 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
78 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
81 TEST_F(RuckigTests, basic_trajectory_with_custom_limits)
88 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
91 std::vector<double> joint_positions;
93 joint_positions.at(0) += 0.05;
96 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
99 std::unordered_map<std::string, double> vel_limits{ {
"panda_joint1", 1.3 } };
100 std::unordered_map<std::string, double> accel_limits{ {
"panda_joint2", 2.3 }, {
"panda_joint3", 3.3 } };
101 std::unordered_map<std::string, double> jerk_limits{ {
"panda_joint5", 100.0 } };
103 EXPECT_TRUE(smoother_.applySmoothing(*trajectory_, vel_limits, accel_limits, jerk_limits));
109 const double ideal_duration = 0.21025;
117 trajectory_->addSuffixWayPoint(robot_state, 0.0);
121 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
124 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
125 EXPECT_GT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 0.9999 * ideal_duration);
126 EXPECT_LT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 1.5 * ideal_duration);
137 trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
142 auto first_waypoint_input = robot_state;
146 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
148 auto const new_first_waypoint = trajectory_->getFirstWayPointPtr();
149 auto const& variable_names = new_first_waypoint->getVariableNames();
150 for (std::string
const& variable_name : variable_names)
152 EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
153 new_first_waypoint->getVariablePosition(variable_name));
157 int main(
int argc,
char** argv)
159 testing::InitGoogleTest(&argc, argv);
160 return RUN_ALL_TESTS();
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
TEST_F(RuckigTests, basic_trajectory)
int main(int argc, char **argv)