We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 5281dc2 commit b019a76Copy full SHA for b019a76
src/emc/usr_intf/emcrsh.cc
@@ -2375,7 +2375,7 @@ static cmdResponseType getJointVelocity(connectionRecType &ctx)
2375
} else {
2376
std::string jl = "JOINT_VELOCITY";
2377
for (int i = 0; i < emcStatus->motion.traj.joints; i++) {
2378
- jl += fmt::format(" {:f}", emcStatus->motion.joint[joint].velocity);
+ jl += fmt::format(" {:f}", emcStatus->motion.joint[i].velocity);
2379
}
2380
replynl(ctx, jl);
2381
0 commit comments