Skip to content
Snippets Groups Projects
Commit 994f11d5 authored by Johannes Mey's avatar Johannes Mey
Browse files

minor fixes

parent 77c2a669
No related branches found
No related tags found
No related merge requests found
......@@ -34,15 +34,10 @@ bool TrajectoryUtil::computePathToPose(moveit::planning_interface::MoveGroupInte
robot_trajectory::RobotTrajectory rt(group.getCurrentState()->getRobotModel(), "panda_arm");
rt.setRobotTrajectoryMsg(*group.getCurrentState(), trajectory_msg);
trajectory_processing::IterativeParabolicTimeParameterization iptp{};
iptp.computeTimeStamps(rt);
if (iptp.computeTimeStamps(rt, maxVelocityFactor)) {
ROS_INFO("Computed time stamps.");
rt.getRobotTrajectoryMsg(trajectory_msg);
plan.trajectory_ = trajectory_msg;
ROS_ERROR_STREAM("After second time parameterization, the trajectory takes " << rt.getDuration() << "s");
} else {
ROS_ERROR("Computation of cartesian path has failed.");
return false;
......@@ -50,6 +45,7 @@ bool TrajectoryUtil::computePathToPose(moveit::planning_interface::MoveGroupInte
} else if (pathType == FLUID_PATH) {
if (group.plan(plan) != moveit::planning_interface::MoveItErrorCode::SUCCESS) {
ROS_ERROR_STREAM("Computation of fluid path has failed. Path was motion to:\n" << targetPose);
return false;
}
} else {
ROS_ERROR("Invalid type of path provided.");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment