Max Number of Points in Cartesian Path
I've been trying to use ROS and Moveit to simulate a tool path which is made up of about 7600 points. I seem to always have issues around point 115, where it will stop calculating poses but still return a success for some reason. Most of the pertinent sections of code are pasted below.
geometry_msgs::Pose target_pose2;
tf2::Quaternion TEMP;
tf2::convert(interm1,interm_pose); // this goal is reachable in a friendly manner.
tf2::Vector3 point, Tpoint;
int i,j;
int numlines;
double datain;
double x,y,z,w,p,r;
std::ifstream infile("Run1_11-22-16.dt");
//std::ifstream infile("Surf11.dt");
std::string line;
std::getline(infile,line);
std::cout<< infile.is_open() << std::endl;
try
{
numlines = std::stoi(line);
std::cout << "Your answer : " << numlines << std::endl;
}
catch (const std::invalid_argument& e)
{
std::cout << "Invalid answer : " << line << std::endl;
}
catch (const std::out_of_range& e)
{
std::cout << "Invalid answer : " << line << std::endl;
}
// make for(i = 1;i<=numlines;i++) for full toolpath
for(i = 1;i<=numlines;i++){
std::getline(infile,line);
datain = std::stod(line);
switch(i%7) {
case 1 : x = datain/1000;
break;
case 2 : y = datain/1000;
break;
case 3 : z = datain/1000;
break;
case 4 : w = datain*pi/180;
break;
case 5 : p = datain*pi/180;
break;
case 6 : r = datain*pi/180;
break;
default : break;
}
if((i%7) == 0){
point[0] = x;
point[1] = y;
point[2] = z;
Tpoint = UFinv*point;
// here I want to put x,y,z,w,p,r into a std::vector<> object, turn wpr into a quaternion, and push the waypoint for ros.
//std::cout<<x<< ' '<<y<<' '<<z<<' '<<w<<' '<<p<<' '<<r<<std::endl;
q1.setRotation(ax2,w);
q2.setRotation(ax1,p);
q3.setRotation(ax3,r);
interm2 = q3*q2*q1; // composition of 3 quaternions representing rotations about x,y, and z respectively.
TEMP = UFinv.getRotation();
interm1 = interm2*TF; // composing current Toolpath orientation with the UserFrame orientation
tf2::convert(interm2,interm_pose); // converting tf::Quaternion to geometry_msgs::Quaternion;
target_pose2.position.x = UFtrans[0] + Tpoint[0];
target_pose2.position.y = UFtrans[1] + Tpoint[1];
target_pose2.position.z = UFtrans[2] + Tpoint[2];
target_pose2.orientation.x = interm_pose.x;
target_pose2.orientation.y = interm_pose.y;
target_pose2.orientation.z = interm_pose.z;
target_pose2.orientation.w = interm_pose.w;
waypoints.push_back(target_pose2);
}
}
moveit_msgs::RobotTrajectory trajectory;
double fraction = move_group.computeCartesianPath(waypoints,
0.02, // eef_step
1, // jump_threshold
trajectory);
ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",fraction * 100.0);
sleep(10);
So my questions are: 1. Is there a limit on the maximum number of waypoints one can have? 2. Does anyone have any idea why it suddenly stops calculating trajectories around point 115.