37 #include <gtest/gtest.h> 39 #include <boost/filesystem/path.hpp> 40 #include <urdf_parser/urdf_parser.h> 41 #include <moveit_resources/config.h> 49 moveit::core::RobotModelConstPtr
loadModel();
60 urdf::ModelInterfaceSharedPtr urdf_model;
62 boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
64 std::fstream xml_file((res_path /
"pr2_description/urdf/robot.xml").
string().c_str(), std::fstream::in);
66 while (xml_file.good())
69 std::getline(xml_file, line);
70 xml_string += (line +
"\n");
73 urdf_model = urdf::parseURDF(xml_string);
75 srdf_model->initFile(*urdf_model, (res_path /
"pr2_description/srdf/robot.xml").
string());
97 for (i = 0; i < num; i++)
99 state.setVariablePosition(idx[0], 1.0);
110 double acc_i = 0.0,
double acc_f = 0.0)
113 const double max = 2.0;
127 for (i = 0; i < num; i++)
129 state.setVariablePosition(idx[0], i * max / num);
134 state.setVariablePosition(idx[0], max);
148 std::cout <<
" Trajectory Points" << std::endl;
149 for (
unsigned i = 0; i < count; i++)
153 point->getVariablePosition(idx[0]), point->getVariableVelocity(idx[0]),
154 point->getVariableAcceleration(idx[0]));
157 robot_state::RobotStatePtr prev = trajectory.
getWayPointPtr(i - 1);
159 (point->getVariableAcceleration(idx[0]) - prev->getVariableAcceleration(idx[0])) /
166 TEST(TestTimeParameterization, TestIterativeParabolic)
173 std::cout <<
"IterativeParabolicTimeParameterization took " << (
ros::WallTime::now() - wt).toSec() << std::endl;
178 TEST(TestTimeParameterization, TestIterativeSpline)
185 std::cout <<
"IterativeSplineParameterization took " << (
ros::WallTime::now() - wt).toSec() << std::endl;
190 TEST(TestTimeParameterization, TestIterativeSplineAddPoints)
197 std::cout <<
"IterativeSplineParameterization with added points took " << (
ros::WallTime::now() - wt).toSec()
203 TEST(TestTimeParameterization, TestRepeatedPoint)
213 int main(
int argc,
char** argv)
215 testing::InitGoogleTest(&argc, argv);
216 return RUN_ALL_TESTS();
Core components of MoveIt!
robot_state::RobotStatePtr & getWayPointPtr(std::size_t index)
void printTrajectory(robot_trajectory::RobotTrajectory &trajectory)
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
int main(int argc, char **argv)
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
TEST(TestTimeParameterization, TestIterativeParabolic)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const
const robot_model::JointModelGroup * getGroup() const
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Maintain a sequence of waypoints and the time durations between these waypoints.
def xml_string(rootXml, addHeader=True)
This class modifies the timestamps of a trajectory to respect velocity and acceleration constraints...
std::size_t getWayPointCount() const
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group...
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
int initRepeatedPointTrajectory(robot_trajectory::RobotTrajectory &trajectory)
const robot_model::RobotModelConstPtr & getRobotModel() const
int initStraightTrajectory(robot_trajectory::RobotTrajectory &trajectory, double vel_i=0.0, double vel_f=0.0, double acc_i=0.0, double acc_f=0.0)
moveit::core::RobotModelConstPtr loadModel()
void addSuffixWayPoint(const robot_state::RobotState &state, double dt)
Add a point to the trajectory.
double max(double a, double b)
#define EXPECT_TRUE(args)
moveit::core::RobotModelConstPtr rmodel
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints. Initial/final velocities and accelerations may be specified in the trajectory. Velocity and acceleration limits are specified in the model.