41 #include <gtest/gtest.h>
75 EXPECT_TRUE(trajectory->empty()) <<
"Generated trajectory not empty";
77 double duration_from_previous = 0.1;
78 std::size_t waypoint_count = 5;
79 for (std::size_t ix = 0; ix < waypoint_count; ++ix)
80 trajectory->addSuffixWayPoint(*
robot_state_, duration_from_previous);
82 EXPECT_EQ(trajectory->getDuration(), duration_from_previous * waypoint_count)
83 <<
"Generated trajectory duration incorrect";
84 EXPECT_EQ(waypoint_count, trajectory->getWayPointDurations().size())
85 <<
"Generated trajectory has the wrong number of waypoints";
88 void copyTrajectory(
const robot_trajectory::RobotTrajectoryPtr& trajectory,
89 robot_trajectory::RobotTrajectoryPtr& trajectory_copy,
bool deepcopy)
92 trajectory_copy = std::make_shared<robot_trajectory::RobotTrajectory>(*trajectory, deepcopy);
94 EXPECT_EQ(trajectory_copy->getDuration(), trajectory->getDuration());
95 EXPECT_EQ(trajectory_copy->getWayPointDurations().size(), trajectory->getWayPointDurations().size());
104 moveit::core::RobotStatePtr trajectory_first_waypoint = trajectory->getWayPointPtr(0);
106 std::vector<double> trajectory_first_state;
107 trajectory_first_waypoint->copyJointGroupPositions(
arm_jmg_name_, trajectory_first_state);
110 trajectory_first_state[0] += 0.01;
111 trajectory_first_waypoint->setJointGroupPositions(
arm_jmg_name_, trajectory_first_state);
114 moveit::core::RobotStatePtr trajectory_first_waypoint_after_update = trajectory->getWayPointPtr(0);
115 std::vector<double> trajectory_first_state_after_update;
116 trajectory_first_waypoint_after_update->copyJointGroupPositions(
arm_jmg_name_, trajectory_first_state_after_update);
117 EXPECT_EQ(trajectory_first_state[0], trajectory_first_state_after_update[0]);
120 double trajectory_first_duration_before_update = trajectory->getWayPointDurationFromPrevious(0);
121 double new_duration = trajectory_first_duration_before_update + 0.1;
122 trajectory->setWayPointDurationFromPrevious(0, new_duration);
125 EXPECT_EQ(trajectory->getWayPointDurationFromPrevious(0), new_duration);
136 std::vector<double> trajectory_first_state;
140 trajectory_first_state[0] += 0.01;
145 std::vector<double> trajectory_first_state_after_update;
147 EXPECT_NE(trajectory_first_state[0], trajectory_first_state_after_update[0]);
153 robot_trajectory::RobotTrajectoryPtr trajectory;
154 initTestTrajectory(trajectory);
155 modifyFirstWaypointPtrAndCheckTrajectory(trajectory);
160 robot_trajectory::RobotTrajectoryPtr trajectory;
161 initTestTrajectory(trajectory);
162 modifyFirstWaypointAndCheckTrajectory(trajectory);
167 robot_trajectory::RobotTrajectoryPtr trajectory;
168 initTestTrajectory(trajectory);
169 moveit_msgs::RobotTrajectory initial_trajectory_msg;
170 trajectory->getRobotTrajectoryMsg(initial_trajectory_msg);
172 trajectory->reverse().reverse();
174 moveit_msgs::RobotTrajectory edited_trajectory_msg;
175 trajectory->getRobotTrajectoryMsg(edited_trajectory_msg);
177 EXPECT_EQ(initial_trajectory_msg, edited_trajectory_msg);
182 robot_trajectory::RobotTrajectoryPtr initial_trajectory;
183 initTestTrajectory(initial_trajectory);
184 moveit_msgs::RobotTrajectory initial_trajectory_msg;
185 initial_trajectory->getRobotTrajectoryMsg(initial_trajectory_msg);
195 .
append(*initial_trajectory, 0.1);
203 bool deepcopy =
false;
205 robot_trajectory::RobotTrajectoryPtr trajectory;
206 robot_trajectory::RobotTrajectoryPtr trajectory_copy;
208 initTestTrajectory(trajectory);
209 copyTrajectory(trajectory, trajectory_copy, deepcopy);
210 modifyFirstWaypointPtrAndCheckTrajectory(trajectory);
214 std::vector<double> trajectory_first_state_after_update;
215 trajectory_first_waypoint_after_update.
copyJointGroupPositions(arm_jmg_name_, trajectory_first_state_after_update);
219 std::vector<double> trajectory_copy_first_state_after_update;
221 trajectory_copy_first_state_after_update);
224 EXPECT_EQ(trajectory_first_state_after_update[0], trajectory_copy_first_state_after_update[0]);
229 bool deepcopy =
true;
231 robot_trajectory::RobotTrajectoryPtr trajectory;
232 robot_trajectory::RobotTrajectoryPtr trajectory_copy;
234 initTestTrajectory(trajectory);
235 copyTrajectory(trajectory, trajectory_copy, deepcopy);
236 modifyFirstWaypointPtrAndCheckTrajectory(trajectory);
240 std::vector<double> trajectory_first_state_after_update;
241 trajectory_first_waypoint_after_update.
copyJointGroupPositions(arm_jmg_name_, trajectory_first_state_after_update);
245 std::vector<double> trajectory_copy_first_state_after_update;
247 trajectory_copy_first_state_after_update);
250 EXPECT_NE(trajectory_first_state_after_update[0], trajectory_copy_first_state_after_update[0]);
252 EXPECT_NE(trajectory->getWayPointDurationFromPrevious(0), trajectory_copy->getWayPointDurationFromPrevious(0));
255 int main(
int argc,
char** argv)
257 testing::InitGoogleTest(&argc, argv);
258 return RUN_ALL_TESTS();