chris-smith / Baxtercpp

In progress tests and implementations of Baxter's functionality in C++
1 stars 1 forks source link

Orientation of Baxter Gripper #1

Open ktiwari9 opened 10 years ago

ktiwari9 commented 10 years ago

Hey there, I am new to ROS and Baxter. I am learning ROS Hydro and for my project i need to use a Baxter to grab a printed circuit board. I have a vision module that detects the printed circuit board in the environment but I do not know how to orient the gripper according to the orientation of the PCB. Is there a piece of your code I could use to realise this ? Is this compatible with ROS Hydro ?

tuftsBaxter commented 10 years ago

Hey

This should definitely be possible. I haven’t used any of my code with ROS Hydro though, so it’s possible there may be some problems there. I’m assuming you’d mostly just need to use the BaxterLimb and -Camera classes, which also depend on geometryTypes.h and baxterGripper.h.

// declare your objects BaxterLimb limb(“right”); BaxterCam cam(“right_hand_camera”);

// get the current wrist position JointPositions jp = limb.joint_positions(); double w2_pos = jp.at(“_w2”);

// get the orientation of the PCB relative to your current hand position double orientation = get_orientation( cam.cvImage() );

// offset wrist position to the desired orientation w2_pos += orientation; jp.at(“_w2”, w2_pos);

// move wrist to new position ros::Duration timeout(5); limb.to_position(jp, timeout);

Presumably, you’d also need to do some kind of inverse kinematics to drop the hand down a little bit to grab the PCB, instead of just rotating the wrist into position. Once you’re there, you can have the limb tell its gripper to close.

limb->gripper.close();

On Jun 1, 2014, at 11:31 AM, Kshitij Tiwari notifications@github.com wrote:

Hey there, I am new to ROS and Baxter. I am learning ROS Hydro and for my project i need to use a Baxter to grab a printed circuit board. I have a vision module that detects the printed circuit board in the environment but I do not know how to orient the gripper according to the orientation of the PCB. Is there a piece of your code I could use to realise this ? Is this compatible with ROS Hydro ?

— Reply to this email directly or view it on GitHub.

ktiwari9 commented 10 years ago

So basically what I understood is that I create my own main.cpp file which looks like :

include "baxterCam.h"

include "baxterLimb.h"

include "baxterGripper.h"

include "geometryTypes.h"

//void setup_pid(BaxterLimb&);

int main(int argc, char\ argv) { ros::init(argc, argv, "Background_Controller_Test");

//declare objects BaxterLimb limb("right"); BackgroundController* bc = new BackgroundController(&limb); BaxterCamera cam("right_hand_camera"); cam.display(); bc->start();

setup_pid(limb);
std::cout<<"you should see \"running thread\" now\n";
//ros::Duration(10).sleep();

//// Get current wrist position : JointPositions jp = limb.joint_positions(); double w2_pose = jp.at("_w2);

std::vector<double> pos(NUMJOINTS, 0);
pos[0] = PI/4;
jp.angles = pos;
bc->set(jp);

//get orientation of PCB with respect to current hand position : double orientation =get_orientation(cam.cvImage());

//offset wrist to desired location w2_pos += orientation; jp.at("_w2",w2_pos);

//moving wrist to position ros ::Duration timeout (5); limb.to_position(jp_timeout);

///// DO IK TO LOWER THE LIMB TO REACH THE PCB

limb -> gripper.close(); }

Is this correct or do I add something more ?

tuftsBaxter commented 10 years ago

Pretty close. You don’t need a couple of the things in there - the BaxterLimb to_position() method uses Baxter’s internal position controller, so it’s not necessary to set any of the PID parameters, although you may want to set the allowable error for each joint - that way the to_position() method will terminate upon “arrival". If you don’t set the allowable error it should just timeout though, so it wouldn’t be a huge deal either way. Also, the background controller is still, and may remain, experimental. You shouldn’t need it for your application though.

include "baxterCam.h"

include "baxterLimb.h"

int main(int argc, char\ argv) {

ros::init(argc, argv, “PCB_Pickup");

//declare objects BaxterLimb limb("right"); BaxterCamera cam("right_hand_camera"); cam.display();

//// Get current wrist position :

JointPositions jp = limb.joint_positions();

double w2_pose = jp.at("_w2);

//get orientation of PCB with respect to current hand position : double orientation = get_orientation( cam.cvImage() );

//offset wrist to desired location w2_pos += orientation; jp.at("_w2",w2_pos);

//moving wrist to position ros::Duration timeout(5); limb.to_position(jp, timeout);

///// DO IK TO LOWER THE LIMB TO REACH THE PCB

limb->gripper.close(); }

On Jun 1, 2014, at 1:07 PM, Kshitij Tiwari notifications@github.com wrote:

So basically what I understood is that I create my own main.cpp file which looks like :

include "baxterCam.h"

include "baxterLimb.h"

include "baxterGripper.h"

//void setup_pid(BaxterLimb&);

int main(int argc, char\ argv) { ros::init(argc, argv, "Background_Controller_Test");

//declare objects BaxterLimb limb("right"); BackgroundController* bc = new BackgroundController(&limb); BaxterCamera cam("right_hand_camera"); cam.display(); bc->start();

setup_pid(limb); std::cout<<"you should see \"running thread\" now\n"; //ros::Duration(10).sleep(); //// Get current wrist position : JointPositions jp = limb.joint_positions(); double w2_pose = jp.at("_w2);

std::vector pos(NUMJOINTS, 0); pos[0] = PI/4; jp.angles = pos; bc->set(jp); //get orientation of PCB with respect to current hand position : double orientation =get_orientation(cam.cvImage());

//offset wrist to desired location w2_pos += orientation; jp.at("_w2",w2_pos);

//moving wrist to position ros ::Duration timeout (5); limb.to_position(jp_timeout);

///// DO IK TO LOWER THE LIMB TO REACH THE PCB

limb -> gripper.close(); }

Is this correct or do I add something more ?

— Reply to this email directly or view it on GitHub.

ktiwari9 commented 10 years ago

Hey there, I took hints from your code and made my own version. I am now using the IK Service to make the arm move to the PCB and grasp it. But i have one problem while pulling out the PCB. Basically I define point A as the pose and orientation of the PCB and point B as a new position but same orientation of the PCB. Simply calling the IK service messes up the wrist joint like this. I do not want the wrist to twist in order to replicate the pulling out motion. So, is there a way to use the IK Service such that I can fix the wrist joint as the pose of the PCB while the IK Service moves the arm from point A to B ? Please advise.

chris-smith commented 10 years ago

I don’t think that’s possible. The IK Service, as far as I’m aware, just shoots back a set of joint angles that satisfy the provided position, but doesn’t check that the joint angles satisfy any conditions. If you’re looking for something else to work like that, you could try incorporating MoveIt! into your code. Another option might be to use the simple IK solver in the BaxterLimb. For small movements, it uses a limited joint set to calculate joint positions for a given endpoint position and wrist angle. It requires that the arm be in a specific type of position, but if you’re just doing pick-and-place from a table, it might satisfy your needs.

For small movements you can use the provided controller void BaxterLimb::set_simple_positions(gv::Point pt, double w2, ros::Duration timeout=ros::Duration(5) ) where the arguments are the coordinate location, the desired wrist angle, and a timeout.

While for larger moves you would probably want to write your own, which would probably look something like while ( /* not arrived */ ) { JointPositions jp = limb.get_simple_positions(point, w2); limb.set_joint_positions(jp); } Ideally, this controller would also interpolate a set of points to move through between your origin and destination, as the solver assumes small changes in angle. Depending on your use case, this may or may not be necessary. In order to use this controller though, you’ll have to pass in a KDL tree, built from Baxter’s URDF, with your constructor. KDL::Tree my_tree; std::string robot_desc_string; nh.param( "robot_description", robot_desc_string, std::string() ); if (!kdl_parser::treeFromString(robot_desc_string, my_tree)){ ROS_ERROR("Failed to construct kdl tree from string"); return 0; } BaxterLimb limb(my_tree, “right”, 1);

If you try out the simple IK solver, Baxter’s arm will always be in a position similar to this.

On Jun 9, 2014, at 8:28 AM, Kshitij Tiwari notifications@github.com wrote:

Hey there, I took hints from your code and made my own version. I am now using the IK Service to make the arm move to the PCB and grasp it. But i have one problem while pulling out the PCB. Basically I define point A as the pose and orientation of the PCB and point B as a new position but same orientation of the PCB. Simply calling the IK service messes up the wrist joint like this. I do not want the wrist to twist in order to replicate the pulling out motion. So, is there a way to use the IK Service such that I can fix the wrist joint as the pose of the PCB while the IK Service moves the arm from point A to B ? Please advise.

— Reply to this email directly or view it on GitHub.