37 #include <gtest/gtest.h>
45 #include <rclcpp/rclcpp.hpp>
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_trajectory_processing.test.test_time_parameterization");
63 RCLCPP_ERROR(LOGGER,
"Need to set the group");
67 const std::vector<int>& idx =
group->getVariableIndexList();
71 for (i = 0; i < num; ++i)
84 const double max = 2.0;
90 RCLCPP_ERROR(LOGGER,
"Need to set the group");
94 const std::vector<int>& idx =
group->getVariableIndexList();
98 for (i = 0; i < num; ++i)
114 const std::vector<int>& idx =
group->getVariableIndexList();
115 trajectory.
print(std::cout, { idx[0] });
118 TEST(TestTimeParameterization, TestIterativeParabolic)
123 auto wt = std::chrono::system_clock::now();
126 std::cout <<
"IterativeParabolicTimeParameterization took " << (std::chrono::system_clock::now() - wt).count()
132 TEST(TestTimeParameterization, TestIterativeSpline)
137 auto wt = std::chrono::system_clock::now();
139 std::cout <<
"IterativeSplineParameterization took " << (std::chrono::system_clock::now() - wt).count() <<
'\n';
144 TEST(TestTimeParameterization, TestIterativeSplineAddPoints)
149 auto wt = std::chrono::system_clock::now();
151 std::cout <<
"IterativeSplineParameterization with added points took "
152 << (std::chrono::system_clock::now() - wt).count() <<
'\n';
157 TEST(TestTimeParameterization, TestRepeatedPoint)
167 int main(
int argc,
char** argv)
169 testing::InitGoogleTest(&argc, argv);
170 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.
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::RobotModelConstPtr & getRobotModel() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
void print(std::ostream &out, std::vector< int > variable_indexes=std::vector< int >()) const
Print information about the trajectory.
const moveit::core::JointModelGroup * getGroup() const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
std::size_t getWayPointCount() const
RobotTrajectory & clear()
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints....
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
moveit::core::RobotModelConstPtr RMODEL
int main(int argc, char **argv)
int initStraightTrajectory(robot_trajectory::RobotTrajectory &trajectory)
void printTrajectory(robot_trajectory::RobotTrajectory &trajectory)
TEST(TestTimeParameterization, TestIterativeParabolic)
robot_trajectory::RobotTrajectory TRAJECTORY(RMODEL, "right_arm")
int initRepeatedPointTrajectory(robot_trajectory::RobotTrajectory &trajectory)