Shows how to use inverse kinematics and planners to move a robot's end-effector safely through the environment. The default manipulator is used for the robot.
#include <vector>
#include <sstream>
#include <boost/thread/thread.hpp>
#include <boost/bind.hpp>
using namespace OpenRAVE;
using namespace std;
namespace cppexamples {
class PlanningIkExample : public OpenRAVEExample
{
public:
virtual void demothread(int argc, char ** argv) {
string scenefilename = "data/pa10grasp2.env.xml";
penv->Load(scenefilename);
vector<RobotBasePtr> vrobots;
penv->GetRobots(vrobots);
for(size_t i = 0; i < probot->GetManipulators().size(); ++i) {
if( probot->GetManipulators()[i]->GetName().find("arm") != string::npos ) {
probot->SetActiveManipulator(probot->GetManipulators()[i]);
break;
}
}
penv->Add(pikfast,true,"");
stringstream ssin,ssout;
vector<dReal> vsolution;
ssin <<
"LoadIKFastSolver " << probot->GetName() <<
" " << (int)
IKP_Transform6D;
if( !pikfast->SendCommand(ssout,ssin) ) {
}
if( !pmanip->GetIkSolver()) {
}
penv->Add(pbasemanip,true,probot->GetName());
while(IsOk()) {
{
EnvironmentMutex::scoped_lock lock(penv->GetMutex());
Transform t = pmanip->GetEndEffectorTransform();
ssin.str("");
ssin.clear();
ssin << "MoveToHandPosition pose " << t;
if( !pbasemanip->SendCommand(ssout,ssin) ) {
continue;
}
}
while(!probot->GetController()->IsDone() && IsOk()) {
boost::this_thread::sleep(boost::posix_time::milliseconds(1));
}
}
}
};
}
int main(
int argc,
char ** argv)
{
return example.
main(argc,argv);
}