Go to the documentation of this file.
37 #include <gtest/gtest.h>
67 for (i = 0; i < num; i++)
80 const double max = 2.0;
94 for (i = 0; i < num; i++)
115 std::cout <<
" Trajectory Points" << std::endl;
116 for (
unsigned i = 0; i < count; i++)
120 point->getVariablePosition(idx[0]),
point->getVariableVelocity(idx[0]),
121 point->getVariableAcceleration(idx[0]));
126 (
point->getVariableAcceleration(idx[0]) -
prev->getVariableAcceleration(idx[0])) /
133 TEST(TestTimeParameterization, TestIterativeParabolic)
140 std::cout <<
"IterativeParabolicTimeParameterization took " << (
ros::WallTime::now() - wt).toSec() << std::endl;
145 TEST(TestTimeParameterization, TestIterativeSpline)
152 std::cout <<
"IterativeSplineParameterization took " << (
ros::WallTime::now() - wt).toSec() << std::endl;
157 TEST(TestTimeParameterization, TestIterativeSplineAddPoints)
164 std::cout <<
"IterativeSplineParameterization with added points took " << (
ros::WallTime::now() - wt).toSec()
170 TEST(TestTimeParameterization, TestRepeatedPoint)
180 int main(
int argc,
char** argv)
182 testing::InitGoogleTest(&argc, argv);
183 return RUN_ALL_TESTS();
robot_trajectory::RobotTrajectory TRAJECTORY(RMODEL, "right_arm")
std::size_t getWayPointCount() const
const moveit::core::JointModelGroup * getGroup() const
moveit::core::RobotModelConstPtr RMODEL
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
const moveit::core::RobotModelConstPtr & getRobotModel() const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Maintain a sequence of waypoints and the time durations between these waypoints.
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
int initStraightTrajectory(robot_trajectory::RobotTrajectory &trajectory)
#define EXPECT_TRUE(args)
int initRepeatedPointTrajectory(robot_trajectory::RobotTrajectory &trajectory)
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.
RobotTrajectory & clear()
int main(int argc, char **argv)
std::chrono::system_clock::time_point point
void printTrajectory(robot_trajectory::RobotTrajectory &trajectory)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
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::RobotStatePtr & getWayPointPtr(std::size_t index)
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints....
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
TEST(TestTimeParameterization, TestIterativeParabolic)
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15