15 #include <yarp/os/Log.h>
16 #include <yarp/os/Network.h>
17 #include <yarp/os/Time.h>
22 #define CARTSLV_DEFAULT_PER 20
23 #define CARTSLV_DEFAULT_TOL 1e-4
24 #define CARTSLV_DEFAULT_CONSTR_TOL 1e-6
25 #define CARTSLV_DEFAULT_MAXITER 200
26 #define CARTSLV_WEIGHT_2ND_TASK 0.01
27 #define CARTSLV_WEIGHT_3RD_TASK 0.01
28 #define CARTSLV_UNCTRLEDJNTS_THRES 1.0
31 using namespace yarp::os;
32 using namespace yarp::sig;
34 using namespace yarp::math;
45 if (!
cmd.read(connection))
48 slv->respond(
cmd,reply);
49 if (ConnectionWriter *writer=connection.getWriter())
65 xd.resize(maxLen,0.0);
77 void InputPort::set_dof(
const Vector &_dof)
79 lock_guard<mutex> lck(mtx);
85 Vector InputPort::get_dof()
87 lock_guard<mutex> lck(mtx);
94 Vector InputPort::get_xd()
96 lock_guard<mutex> lck(mtx);
103 void InputPort::reset_xd(
const Vector &_xd)
105 lock_guard<mutex> lck(mtx);
112 bool InputPort::isNewDataEvent()
125 bool InputPort::handleTarget(Bottle *b)
129 lock_guard<mutex> lck(mtx);
130 size_t len=
std::min(b->size(),maxLen);
131 for (
size_t i=0; i<len; i++)
132 xd[i]=b->get(i).asFloat64();
141 bool InputPort::handleDOF(Bottle *b)
148 dof.resize(b->size());
149 for (
int i=0; i<b->size(); i++)
150 dof[i]=b->get(i).asInt32();
162 bool InputPort::handlePose(
const int newPose)
186 bool InputPort::handleMode(
const int newMode)
208 void InputPort::onRead(Bottle &b)
217 if (CartesianHelper::getTokenOption(b,&token))
225 yWarning(
"%s: got incomplete %s command",slv->slvName.c_str(),
230 yWarning(
"%s: expected %s data",slv->slvName.c_str(),
235 yWarning(
"%s: got incomplete %s command",slv->slvName.c_str(),
242 slv->prepareJointsRestTask();
250 yWarning(
"%s: expected %s data",slv->slvName.c_str(),
254 yWarning(
"%s: missing %s data; it shall be present",
260 void SolverCallback::exec(
const Vector &xd,
const Vector &q)
262 slv->send(xd,slv->prt->chn->EndEffPose(),
CTRL_RAD2DEG*q,slv->pToken);
267 CartesianSolver::CartesianSolver(
const string &_slvName) :
303 string partName=partOpt.find(
"part").asString();
304 PolyDriver *pDrv=NULL;
306 double t0=Time::now();
311 pDrv=
new PolyDriver(
const_cast<Property&
>(partOpt));
312 bool ok=pDrv->isValid();
316 yInfo(
"%s: Checking if %s part is active ... ok",
317 slvName.c_str(),partName.c_str());
323 yInfo(
"%s: Checking if %s part is active ... not yet: still %.1f [s] to timeout expiry",
324 slvName.c_str(),partName.c_str(),dt>0.0?dt:0.0);
326 double t1=Time::now();
327 while (Time::now()-t1<1.0)
346 yInfo(
"%s: aligning joints bounds ...",
slvName.c_str());
347 for (
int i=0; i<
prt->
num; i++)
349 yInfo(
"part #%d: %s",i,
prt->
prp[i].find(
"part").asString().c_str());
350 for (
int j=0; j<
jnt[i]; j++)
354 yError(
"joint #%d: failed getting limits!",cnt);
358 yInfo(
"joint #%d: [%g, %g] deg",cnt,
min,
max);
378 yError(
"#%d>#%d: requested out of range axis!",
381 yError(
"joint #%d: requested wrong bounds [%g,%g]!",
394 yWarning(
"joint #%d: requested out of range limit!",axis);
415 for (
unsigned int i=0; i<
prt->
chn->
getN(); i++)
416 if ((*
prt->
chn)[i].isBlocked())
430 for (
int i=0; i<
prt->
num; i++)
432 bool ok=
enc[i]->getEncoders(fbTmp.data());
435 ok=
enc[i]->getEncoders(fbTmp.data());
441 for (
int j=0; j<
jnt[i]; j++)
445 if ((*
prt->
chn)[chainCnt].isBlocked())
455 yWarning(
"%s: timeout detected on part %s!",
456 slvName.c_str(),
prt->
prp[i].find(
"part").asString().c_str());
509 for (
unsigned int i=0; i<
prt->
chn->
getN(); i++)
510 reply.addInt32(
int(!(*
prt->
chn)[i].isBlocked()));
519 int vcb=command.get(0).asVocab32();
528 if (command.size()>1)
530 switch (command.get(1).asVocab32())
551 if (priority==
"position")
564 if (
inPort->get_contMode())
575 if (command.size()>2)
577 int axis=command.get(2).asInt32();
611 Bottle &dofPart=reply.addList();
636 Bottle &payLoad=reply.addList();
639 Bottle &posPart=payLoad.addList();
643 Bottle &weightsPart=payLoad.addList();
644 for (
size_t i=0; i<
w_2ndTask.length(); i++)
654 Bottle &payLoad=reply.addList();
656 Bottle &tol=payLoad.addList();
657 tol.addString(
"tol");
660 Bottle &constr_tol=payLoad.addList();
661 constr_tol.addString(
"constr_tol");
664 Bottle &maxIter=payLoad.addList();
665 maxIter.addString(
"max_iter");
685 if (command.size()>2)
687 switch (command.get(1).asVocab32())
692 if (
inPort->handlePose(command.get(2).asVocab32()))
703 int type=command.get(2).asVocab32();
723 if (
inPort->handleMode(command.get(2).asVocab32()))
734 if (command.size()>4)
736 int axis=command.get(2).asInt32();
737 double min=command.get(3).asFloat64();
738 double max=command.get(4).asFloat64();
754 int sw=command.get(2).asVocab32();
773 if (
inPort->handleDOF(command.get(2).asList()))
778 Bottle &dofPart=reply.addList();
799 reply.append(restPart);
819 reply.append(restPart);
830 if (Bottle *tipPart=command.get(2).asList())
832 if (tipPart->size()>=7)
835 for (
size_t i=0; i<
x.length(); i++)
836 x[i]=tipPart->get(i).asFloat64();
839 for (
size_t i=0; i<o.length(); i++)
840 o[i]=tipPart->get(i+
x.length()).asFloat64();
842 Matrix HN=axis2dcm(o);
861 if (Bottle *payLoad=command.get(2).asList())
863 if (payLoad->size()>=3)
865 int n=payLoad->get(0).asInt32();
866 Bottle *posPart=payLoad->get(1).asList();
867 Bottle *weightsPart=payLoad->get(2).asList();
869 if ((posPart!=NULL) && (weightsPart!=NULL))
871 if ((posPart->size()>=3) && (weightsPart->size()>=3))
876 for (
size_t i=0; i<
w_2ndTask.length(); i++)
877 w_2ndTask[i]=weightsPart->get(i).asFloat64();
898 if (Bottle *payLoad=command.get(2).asList())
901 if (payLoad->check(
"tol"))
903 slv->
setTol(payLoad->find(
"tol").asFloat64());
907 if (payLoad->check(
"constr_tol"))
913 if (payLoad->check(
"max_iter"))
950 else if (b_xd->size()<3)
959 Vector xd(b_xd->size());
960 for (
size_t i=0; i<xd.length(); i++)
961 xd[i]=b_xd->get(i).asFloat64();
968 for (
unsigned int i=0; i<len; i++)
991 double t0=Time::now();
993 double t1=Time::now();
1006 for (
unsigned int i=0; i<
prt->
chn->
getN(); i++)
1047 reply.addString(
"suspended");
1048 else if (isRunning())
1049 reply.addString(
"running");
1051 reply.addString(
"not_started");
1058 Property options(command.toString().c_str());
1059 yInfo(
"Configuring with options: %s",options.toString().c_str());
1072 reply.addVocab32(
"many");
1073 reply.addString(
"***** commands");
1083 reply.addString(
"***** options");
1097 reply.addString(
"***** values");
1145 const Vector &
x,
const Vector &q,
1149 Vector x_=
x.subVector(0,(
unsigned int)xd.length()-1);
1151 printf(
" Request type = %s\n",typ.c_str());
1152 printf(
" Target rxPose [m] = %s\n",xd.toString().c_str());
1153 printf(
" Target txPose [m] = %s\n",x_.toString().c_str());
1154 printf(
"Target txJoints [deg] = %s\n",q.toString().c_str());
1155 printf(
" computed in [s] = %g\n",t);
1165 for (
unsigned int i=0; i<
prt->
chn->
getN(); i++)
1166 if (!(
dof[i]=!(*
prt->
chn)[i].isBlocked()))
1178 for (
unsigned int i=0; i<len; i++)
1182 else if (_dof[i]!=0.0)
1202 for (
unsigned int i=0; i<len; i++)
1216 Bottle &b=reply->addList();
1233 for (
size_t i=0; i<len; i++)
1235 double val=options->get(i).asInt32();
1244 Bottle &b=reply->addList();
1257 for (
size_t i=0; i<len; i++)
1261 else if (_dof[i]!=
dof[i])
1274 yWarning(
"%s already configured",
slvName.c_str());
1281 yError(
"Detected errors while processing parts description!");
1286 yInfo()<<
"DH Table: "<<DHTable.toString();
1288 if (options.check(
"ping_robot_tmo"))
1293 for (
int i=0; i<
prt->
num; i++)
1295 yInfo(
"Allocating device driver for %s ...",
1296 prt->
prp[i].find(
"part").asString().c_str());
1300 new PolyDriver(
prt->
prp[i]);
1302 if (!pDrv->isValid())
1305 yError(
"Device driver not available!");
1311 IControlLimits *pLim;
1315 if (!pDrv->view(pLim) || !pDrv->view(pEnc))
1318 yError(
"Problems acquiring interfaces!");
1323 pEnc->getAxes(&joints);
1331 if (joints>remainingJoints)
1332 joints=remainingJoints;
1334 remainingJoints-=joints;
1336 int *rmpTmp=
new int[joints];
1337 for (
int j=0; j<joints; j++)
1338 rmpTmp[j]=
prt->
rvs[i]?(joints-j-1):j;
1340 drv.push_back(pDrv);
1341 lim.push_back(pLim);
1342 enc.push_back(pEnc);
1343 jnt.push_back(joints);
1344 rmp.push_back(rmpTmp);
1358 if (Bottle *v=options.find(
"dof").asList())
1360 Vector _dof(v->size());
1361 for (
size_t i=0; i<_dof.length(); i++)
1362 _dof[i]=v->get(i).asInt32();
1371 yError(
"Unable to retrieve joints limits!");
1378 setPeriod((
double)
period/1000.0);
1390 if (options.check(
"verbosity"))
1402 if (options.check(
"interPoints"))
1414 double lower_bound_inf, upper_bound_inf;
1435 outPort=
new BufferedPort<Bottle>;
1498 for (
unsigned int i=0; i<
prt->
chn->
getN(); i++)
1500 if (!(*
prt->
chn)[i].isBlocked())
1563 for (
size_t i=0; i<
drv.size(); i++)
1569 for (
size_t i=0; i<
rmp.size(); i++)
1589 yInfo(
"%s closed",
slvName.c_str());
1598 yError(
"%s not configured!",
slvName.c_str());
1610 yInfo(
"%s started successfully",
slvName.c_str());
1612 yError(
"%s did not start!",
slvName.c_str());
1620 yWarning(
"%s is already suspended",
slvName.c_str());
1623 PeriodicThread::suspend();
1624 yInfo(
"%s suspended",
slvName.c_str());
1635 PeriodicThread::resume();
1636 yInfo(
"%s resumed",
slvName.c_str());
1639 yWarning(
"%s is already running",
slvName.c_str());
1661 Vector unctrlJoints;
1679 yInfo(
"%s: detected movements on uncontrolled joints (norm=%g>%g deg)",
1684 if (
inPort->isNewDataEvent())
1694 Vector xd=
inPort->get_xd();
1695 if (
inPort->get_tokenPtr())
1712 double t0=Time::now();
1714 double t1=Time::now();
1744 yInfo(
"Stopping %s ...",
slvName.c_str());
1764 string part_type=
type;
1766 if (options.check(
"type"))
1768 type=options.find(
"type").asString();
1769 part_type=
type.substr(0,
type.find(
"_"));
1770 if ((part_type!=
"left") && (part_type!=
"right"))
1771 type=part_type=
"right";
1773 size_t underscore=
type.find(
'_');
1774 if (underscore!=string::npos)
1778 string robot=options.check(
"robot",Value(
"icub")).asString();
1779 Property optTorso(
"(device remote_controlboard)");
1780 Property optArm(
"(device remote_controlboard)");
1782 string partTorso =
"torso";
1783 string remoteTorso=
"/"+robot+
"/"+partTorso;
1784 string localTorso =
"/"+
slvName+
"/"+partTorso;
1785 optTorso.put(
"remote",remoteTorso);
1786 optTorso.put(
"local",localTorso);
1787 optTorso.put(
"robot",robot);
1788 optTorso.put(
"part",partTorso);
1790 string partArm =part_type==
"left"?
"left_arm":
"right_arm";
1791 string remoteArm=
"/"+robot+
"/"+partArm;
1792 string localArm =
"/"+
slvName+
"/"+partArm;
1793 optArm.put(
"remote",remoteArm);
1794 optArm.put(
"local",localArm);
1795 optArm.put(
"robot",robot);
1796 optArm.put(
"part",partArm);
1800 p->chn=
p->lmb->asChain();
1802 p->prp.push_back(optTorso);
1803 p->prp.push_back(optArm);
1805 p->rvs.push_back(
false);
1838 for (
size_t i=0; i<len; i++)
1842 if (!(((newDOF[3]!=0.0) && (newDOF[4]!=0) && (newDOF[5]!=0)) ||
1843 ((newDOF[3]==0.0) && (newDOF[4]==0.0) && (newDOF[5]==0.0))))
1847 newDOF[3]=newDOF[4]=newDOF[5]=
dof[3];
1849 yWarning(
"%s: attempt to set one shoulder's joint differently from others",
slvName.c_str());
1860 string part_type=
type;
1862 if (options.check(
"type"))
1864 type=options.find(
"type").asString();
1865 part_type=
type.substr(0,
type.find(
"_"));
1866 if ((part_type!=
"left") && (part_type!=
"right"))
1867 type=part_type=
"right";
1869 size_t underscore=
type.find(
'_');
1870 if (underscore!=string::npos)
1874 string robot=options.check(
"robot",Value(
"icub")).asString();
1875 Property optLeg(
"(device remote_controlboard)");
1877 string partLeg =part_type==
"left"?
"left_leg":
"right_leg";
1878 string remoteLeg=
"/"+robot+
"/"+partLeg;
1879 string localLeg =
"/"+
slvName+
"/"+partLeg;
1881 optLeg.put(
"remote",remoteLeg);
1882 optLeg.put(
"local",localLeg);
1883 optLeg.put(
"robot",robot);
1884 optLeg.put(
"part",partLeg);
1888 p->chn=
p->lmb->asChain();
1890 p->prp.push_back(optLeg);
1891 p->rvs.push_back(
false);
bool read(ConnectionReader &connection)
static void addVectorOption(yarp::os::Bottle &b, const int vcb, const yarp::sig::Vector &v)
static yarp::os::Bottle * getJointsOption(const yarp::os::Bottle &b)
Retrieves the joints configuration data.
static yarp::os::Bottle * getTargetOption(const yarp::os::Bottle &b)
Retrieves commanded target data from a bottle.
static void addTokenOption(yarp::os::Bottle &b, const double token)
Appends to a bottle a token to be exchanged with the solver.
Abstract class defining the core of on-line solvers.
yarp::sig::Vector idx_3rdTask
std::deque< yarp::dev::IControlLimits * > lim
yarp::os::BufferedPort< yarp::os::Bottle > * outPort
virtual yarp::sig::Vector & encodeDOF()
virtual bool handleJointsRestWeights(const yarp::os::Bottle *options, yarp::os::Bottle *reply=NULL)
bool setLimits(int axis, double min, double max)
virtual bool open(yarp::os::Searchable &options)
Configure the solver and start it up.
std::condition_variable cv_dofEvent
virtual PartDescriptor * getPartDesc(yarp::os::Searchable &options)=0
yarp::sig::Vector xd_2ndTask
bool changeDOF(const yarp::sig::Vector &_dof)
virtual yarp::sig::Vector solve(yarp::sig::Vector &xd)
virtual void respond(const yarp::os::Bottle &command, yarp::os::Bottle &reply)
yarp::sig::Vector w_3rdTask
RpcProcessor * cmdProcessor
virtual void interrupt()
Interrupt the open() method waiting for motor parts to be ready.
yarp::sig::Vector restWeights
virtual void resume()
Resume the solver's main loop.
void countUncontrolledJoints()
yarp::sig::Matrix swLimits
std::deque< yarp::dev::IEncoders * > enc
friend class RpcProcessor
yarp::sig::Matrix hwLimits
virtual void afterStart(bool)
virtual bool decodeDOF(const yarp::sig::Vector &_dof)
yarp::sig::Vector restJntPos
virtual void threadRelease()
yarp::sig::Vector unctrlJointsOld
void printInfo(const std::string &typ, const yarp::sig::Vector &xd, const yarp::sig::Vector &x, const yarp::sig::Vector &q, const double t)
virtual bool handleJointsRestPosition(const yarp::os::Bottle *options, yarp::os::Bottle *reply=NULL)
void latchUncontrolledJoints(yarp::sig::Vector &joints)
virtual void suspend()
Suspend the solver's main loop.
virtual ~CartesianSolver()
Default destructor.
friend class SolverCallback
yarp::dev::PolyDriver * waitPart(const yarp::os::Property &partOpt)
void getFeedback(const bool wait=false)
virtual void close()
Stop the solver and dispose it.
void fillDOFInfo(yarp::os::Bottle &reply)
yarp::sig::Vector w_2ndTask
virtual void prepareJointsRestTask()
void send(const yarp::sig::Vector &xd, const yarp::sig::Vector &x, const yarp::sig::Vector &q, double *tok)
std::deque< yarp::dev::PolyDriver * > drv
yarp::sig::Vector qd_3rdTask
bool isNewDOF(const yarp::sig::Vector &_dof)
virtual bool threadInit()
Class for dealing with additional iCub arm's constraints.
virtual PartDescriptor * getPartDesc(yarp::os::Searchable &options)
virtual bool decodeDOF(const yarp::sig::Vector &_dof)
virtual bool open(yarp::os::Searchable &options)
Configure the solver and start it up.
A class for defining the iCub Arm.
virtual PartDescriptor * getPartDesc(yarp::os::Searchable &options)
A class for defining the iCub Leg.
bool setHN(const yarp::sig::Matrix &_HN)
Sets HN, the rigid roto-translation matrix from the Nth frame to the end-effector.
bool releaseLink(const unsigned int i)
Releases the ith Link.
void clear()
Removes all Links.
bool setBlockingValue(const unsigned int i, double Ang)
Changes the value of the ith blocked Link.
yarp::sig::Vector EndEffPose(const bool axisRep=true)
Returns the coordinates of end-effector.
yarp::sig::Vector getAng()
Returns the current free joint angles values.
yarp::sig::Vector setAng(const yarp::sig::Vector &q)
Sets the free joint angles to values of q[i].
unsigned int getN() const
Returns the number of Links belonging to the Chain.
unsigned int getDOF() const
Returns the current number of Chain's DOF.
bool blockLink(const unsigned int i, double Ang)
Blocks the ith Link at the a certain value of its joint angle.
Class for inverting chain's kinematics based on IpOpt lib.
void attachLIC(iKinLinIneqConstr &lic)
Attach a iKinLinIneqConstr object in order to impose constraints of the form lB <= C*q <= uB.
void setTol(const double tol)
Sets cost function tolerance.
double getConstrTol() const
Retrieves constraints tolerance.
std::string get_posePriority() const
Returns the Pose priority settings.
void setConstrTol(const double constr_tol)
Sets constraints tolerance.
void setUserScaling(const bool useUserScaling, const double _obj_scaling, const double _x_scaling, const double _g_scaling)
Enables/disables user scaling factors.
bool set_posePriority(const std::string &priority)
Sets the Pose priority for weighting more either position or orientation while reaching in full pose.
iKinLinIneqConstr & getLIC()
Returns a reference to the attached Linear Inequality Constraints object.
int getMaxIter() const
Retrieves the current value of Maximum Iteration.
double getTol() const
Retrieves cost function tolerance.
void setMaxIter(const int max_iter)
Sets Maximum Iteration.
void getBoundsInf(double &lower, double &upper)
Returns the lower and upper bounds to represent -inf and +inf.
iKinChain & get2ndTaskChain()
Retrieves the 2nd task's chain.
void set_ctrlPose(const unsigned int _ctrlPose)
Sets the state of Pose control settings.
void specify2ndTaskEndEff(const unsigned int n)
Selects the End-Effector of the 2nd task by giving the ordinal number n of last joint pointing at it.
virtual yarp::sig::Vector solve(const yarp::sig::Vector &q0, yarp::sig::Vector &xd, double weight2ndTask, yarp::sig::Vector &xd_2nd, yarp::sig::Vector &w_2nd, double weight3rdTask, yarp::sig::Vector &qd_3rd, yarp::sig::Vector &w_3rd, int *exit_code=NULL, bool *exhalt=NULL, iKinIterateCallback *iterate=NULL)
Executes the IpOpt algorithm trying to converge on target.
A class for defining the versions of the iCub limbs.
bool toLinksProperties(yarp::os::Property &options)
Provides the links attributes listed in a property object.
double & getLowerBoundInf()
Returns a reference to the internal representation of -inf.
virtual void update(void *)
Updates internal state.
double & getUpperBoundInf()
Returns a reference to the internal representation of +inf.
double norm(const yarp::sig::Matrix &M, int col)
Returns the norm of the vector given in the form: matrix(:,col).
#define IKINCTRL_POSE_FULL
#define IKINCTRL_POSE_XYZ
#define CARTSLV_DEFAULT_TOL
#define CARTSLV_DEFAULT_PER
#define CARTSLV_WEIGHT_3RD_TASK
#define CARTSLV_DEFAULT_MAXITER
#define CARTSLV_DEFAULT_CONSTR_TOL
#define CARTSLV_UNCTRLEDJNTS_THRES
#define CARTSLV_WEIGHT_2ND_TASK
#define IKINSLV_VOCAB_OPT_DOF
#define IKINSLV_VOCAB_CMD_QUIT
#define IKINSLV_VOCAB_VAL_POSE_FULL
#define IKINSLV_VOCAB_CMD_STATUS
#define IKINSLV_VOCAB_OPT_PRIO
#define IKINSLV_VOCAB_VAL_PRIO_XYZ
#define IKINSLV_VOCAB_VAL_OFF
#define IKINSLV_VOCAB_CMD_SUSP
#define IKINSLV_VOCAB_VAL_MODE_TRACK
#define IKINSLV_VOCAB_VAL_MODE_SINGLE
#define IKINSLV_VOCAB_OPT_POSE
#define IKINSLV_VOCAB_OPT_Q
#define IKINSLV_VOCAB_OPT_CONVERGENCE
#define IKINSLV_VOCAB_OPT_MODE
#define IKINSLV_VOCAB_CMD_SET
#define IKINSLV_VOCAB_CMD_ASK
#define IKINSLV_VOCAB_REP_ACK
#define IKINSLV_VOCAB_VAL_ON
#define IKINSLV_VOCAB_CMD_RUN
#define IKINSLV_VOCAB_OPT_TOKEN
#define IKINSLV_VOCAB_OPT_REST_POS
#define IKINSLV_VOCAB_CMD_HELP
#define IKINSLV_VOCAB_CMD_CFG
#define IKINSLV_VOCAB_OPT_VERB
#define IKINSLV_VOCAB_VAL_POSE_XYZ
#define IKINSLV_VOCAB_OPT_TIP_FRAME
#define IKINSLV_VOCAB_CMD_GET
#define IKINSLV_VOCAB_OPT_LIM
#define IKINSLV_VOCAB_OPT_TASK2
#define IKINSLV_VOCAB_OPT_REST_WEIGHTS
#define IKINSLV_VOCAB_REP_NACK
#define IKINSLV_VOCAB_OPT_X
#define IKINSLV_VOCAB_VAL_PRIO_ANG
#define IKINSLV_VOCAB_OPT_XD
std::deque< yarp::os::Property > prp