Kinovarobotics / kinova-ros

ROS packages for Jaco2 and Mico robotic arms
BSD 3-Clause "New" or "Revised" License
363 stars 318 forks source link

Accuracy of cartesian velocity control #395

Closed yuweiDu closed 2 years ago

yuweiDu commented 2 years ago

Hi!

I am using the topic "/j2s6s300_driver/in/cartesian_velocity" to control my arm but I found that the accuracy was not satisfactory. So I wrote a .cpp script to make the arm do periodic translation movements to verify the accuracy of the controller. I set velocity along y-axis as 0.04m/s or -0.04m/s. And duration=5s which means the end-effector should move 20cm along y-axis. However, I observed that the end of the arm move less than 20cm(approximately 16-17cm). I need high accuracy of the cartesian velocity, so is it better for me to compute joint velocity from desired cartesian velocity using the Jacobian matrix. Thank you! I post the code I used for your information.

The start pose was set like this rosrun kinova_demo pose_action_client.py -v j2s6s300 mq -- 0.0 0.30 0.20 0.707 -0.707 0 0

int main(int argc, char **argv)
{

  ros::init(argc, argv, "jacoTraj");
  ros::NodeHandle n;
  ros::Publisher chatter_pub = n.advertise<kinova_msgs::PoseVelocity>("/j2n6s300_driver/in/cartesian_velocity", 1000);

  ros::Rate loop_rate(100);

  int cnt = 0;
  double dt = loop_rate.expectedCycleTime().toSec();
  double duration=5.0;

  while (n.ok()) {
    while(cnt<duration/dt){

      kinova_msgs::PoseVelocity arm_twist_cmd;
      arm_twist_cmd.twist_linear_x  = 0.;
      arm_twist_cmd.twist_linear_y  = 0.04;
      arm_twist_cmd.twist_linear_z  = 0;
      arm_twist_cmd.twist_angular_x = 0.;
      arm_twist_cmd.twist_angular_y = 0.;
      arm_twist_cmd.twist_angular_z = 0.;

      chatter_pub.publish(arm_twist_cmd);
      ros::spinOnce();
      loop_rate.sleep();
      ++cnt;
    }

    cnt = 0;
    while (cnt<duration/dt) {
      Vector9d pva;
      pva = traj_r.position_plan(dt*cnt);
      // std::cout<<desired_vel_<<std::endl;
      kinova_msgs::PoseVelocity arm_twist_cmd;
      arm_twist_cmd.twist_linear_x  = 0.;
      arm_twist_cmd.twist_linear_y  = -0.04;
      arm_twist_cmd.twist_linear_z  = 0.;
      arm_twist_cmd.twist_angular_x = 0.;
      arm_twist_cmd.twist_angular_y = 0.;
      arm_twist_cmd.twist_angular_z = 0.;

      chatter_pub.publish(arm_twist_cmd);
      ros::spinOnce();
      loop_rate.sleep();
      ++cnt;
    }
    cnt = 0;
  }
  return 0;
}
felixmaisonneuve commented 2 years ago

Hi @yuweiDu,

Unfortunately the Jaco2 is not very precise and you won't be able to achieve such degrees of precision. The Jaco2 arm's precision is in order of centimeters (~3-4cm, but can be more) in cartesian mode.

We usually recommend using joint velocities if you require more precision, but even then, you won't be able to be super precise. The arm was not built with this requirement in mind.

Best, Felix