Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Error using KinovaComm::setCartesianPosition() #404

Open
NAEE09 opened this issue Oct 20, 2022 · 1 comment
Open

Error using KinovaComm::setCartesianPosition() #404

NAEE09 opened this issue Oct 20, 2022 · 1 comment

Comments

@NAEE09
Copy link

NAEE09 commented Oct 20, 2022

Hi, I'm using the kinova jaco arm (j2n6s300) without the gripper. As you mentioned in the readme of github "Cartesian position control can be realized by calling kinovaComm::setCartesianPosition()", I am trying to create a subscriber node to control the cartesian position with a PoseStamped message, inside the callback I initialized the Kinovacomm object, and my script is very similar to the pose action server, is there any easy way to implement this function "kinovaComm::setCartesianPosition()"?. On the other hand, the node works fine when I just run the ros master and the node, but I use the kinova with the Summit xl mobile robot and when I run the general launch of both robots , I get the following error:

[ERROR] [1325383471.209385925]:-KinovaCommException: Could not get Cartesian finger position (return code. 1015) [j2n6s300 driver-13] process has died [pid 4694, exit code -11, cmd/home/summit/kinova_ws/devel/lib/kinova_driver/kinova_arm_driver j2n6s300 /j2n6s300_driver/out/joint_state: =/joint_states __name:=j2n6s300_driver __log:=/home/summit/.ros/log/a905a0dc-341c-11e1-8518-54bef7887996/j2n6s300_driver-13*.log] log file: /home/summit/ros/log/a90/summit_xl_control/odom 5a0dc-341c-11e1-8518-54bef7887996/ j2n6s300_driver-13*.log [j2n6s300_driver-13] restarting process process[j2n6s300_driver-13]: starte /tf He name="tf_bd with pid [6708] [INFO] [1325383471.349557673]: kinova_robotType is j2n6s300. [INFO] [1325383471.353764109]: Initializing Kinova USB API (header version: 50308, library version: 5.2.0) [ERROR] [1325383471.387882694]: KinovaCommException: Could not send ba sic trajectory (return code: 2004)

And the robot does not reach the desire pose. Also, it is important to mention, the action client of the demo works well with the general launch.

Any suggestion?

Thanks.

@felixmaisonneuve
Copy link
Contributor

Hi @NAEE09,

The error you get is printed here :

void KinovaComm::getFingerPositions(FingerAngles &fingers)
{
boost::recursive_mutex::scoped_lock lock(api_mutex_);
CartesianPosition kinova_cartesian_position;
memset(&kinova_cartesian_position, 0, sizeof(kinova_cartesian_position)); // zero structure
int result = kinova_api_.getCartesianPosition(kinova_cartesian_position);
if (result != NO_ERROR_KINOVA)
{
throw KinovaCommException("Could not get Cartesian finger position", result);
}
if (num_fingers_ == 2)
{
kinova_cartesian_position.Fingers.Finger3 = 0.0;
}
fingers = FingerAngles(kinova_cartesian_position.Fingers);
}

Since you do not have a gripper, this API call will always fail, so you have to make sure this is never called in your driver.

The kinova_arm driver constantly ppublishes info about the arm, and I think this is were it fails.

This is the function in the driver that updates the topics of your ROS driver :

void KinovaArm::statusTimer(const ros::TimerEvent&)
{
publishJointAngles();
publishToolPosition();
publishToolWrench();
publishFingerPosition();
}

You need to remove the publishFingerPosition() function (that uses getFingerPositions) and you need to modify the publishJointAngles() function also.

In publishJointAngles(), remove every mention to fingers :

FingerAngles fingers;
kinova_comm_.getFingerPositions(fingers);

if(finger_number_==2)
{
// proximal phalanges
joint_state.position[joint_total_number_-4] = fingers.Finger1 * finger_conv_ratio_ * M_PI/180;
joint_state.position[joint_total_number_-3] = fingers.Finger2 * finger_conv_ratio_ * M_PI/180;
// distal phalanges
joint_state.position[joint_total_number_-2] = 0;
joint_state.position[joint_total_number_-1] = 0;
}
else if(finger_number_==3)
{
// proximal phalanges
joint_state.position[joint_total_number_-6] = fingers.Finger1 * finger_conv_ratio_ * M_PI/180;
joint_state.position[joint_total_number_-5] = fingers.Finger2 * finger_conv_ratio_ * M_PI/180;
joint_state.position[joint_total_number_-4] = fingers.Finger3 * finger_conv_ratio_ * M_PI/180;
// distal phalanges
joint_state.position[joint_total_number_-3] = 0;
joint_state.position[joint_total_number_-2] = 0;
joint_state.position[joint_total_number_-1] = 0;
}

If you remove all of this, your driver should be able to launch correctly.

For the kinovaComm::setCartesianPosition(), can you share a brief sample of your code? I am not sure I fully understand what you are doing

Regards,
Felix

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants