|
iCub-main
|
A derived class defining a first abstraction layer on top of actionPrimitives father class. More...
#include <actionPrimitives.h>
Inheritance diagram for iCub::action::ActionPrimitivesLayer1:Public Member Functions | |
| ActionPrimitivesLayer1 () | |
| Default Constructor. | |
| ActionPrimitivesLayer1 (yarp::os::Property &opt) | |
| Constructor. | |
| virtual bool | grasp (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const yarp::sig::Vector &d) |
| Grasp the given target (combined action). | |
| virtual bool | touch (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const yarp::sig::Vector &d) |
| Touch the given target (combined action). | |
| virtual bool | tap (const yarp::sig::Vector &x1, const yarp::sig::Vector &o1, const yarp::sig::Vector &x2, const yarp::sig::Vector &o2, const double execTime=ACTIONPRIM_DISABLE_EXECTIME) |
| Tap the given target (combined action). | |
Public Member Functions inherited from iCub::action::ActionPrimitives | |
| ActionPrimitives () | |
| Default Constructor. | |
| ActionPrimitives (yarp::os::Property &opt) | |
| Constructor. | |
| virtual | ~ActionPrimitives () |
| Destructor. | |
| virtual bool | open (yarp::os::Property &opt) |
| Configure the object. | |
| virtual bool | isValid () const |
| Check if the object is initialized correctly. | |
| virtual void | close () |
| Deallocate the object. | |
| virtual bool | pushAction (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const std::string &handSeqKey, const double execTime=ACTIONPRIM_DISABLE_EXECTIME, ActionPrimitivesCallback *clb=NULL) |
| Insert a combination of arm and hand primitive actions in the actions queue. | |
| virtual bool | pushAction (const yarp::sig::Vector &x, const std::string &handSeqKey, const double execTime=ACTIONPRIM_DISABLE_EXECTIME, ActionPrimitivesCallback *clb=NULL) |
| Insert a combination of arm and hand primitive actions in the actions queue. | |
| virtual bool | pushAction (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const double execTime=ACTIONPRIM_DISABLE_EXECTIME, ActionPrimitivesCallback *clb=NULL) |
| Insert the arm-primitive action reach for target in the actions queue. | |
| virtual bool | pushAction (const yarp::sig::Vector &x, const double execTime=ACTIONPRIM_DISABLE_EXECTIME, ActionPrimitivesCallback *clb=NULL) |
| Insert the arm-primitive action reach for target in the actions queue. | |
| virtual bool | pushAction (const std::string &handSeqKey, ActionPrimitivesCallback *clb=NULL) |
| Insert a hand-primitive action in the actions queue. | |
| virtual bool | pushAction (const std::deque< ActionPrimitivesWayPoint > &wayPoints, ActionPrimitivesCallback *clb=NULL) |
| Insert in the actions queue a trajectory in the operational space parametrized in terms of waypoints. | |
| virtual bool | pushAction (const std::deque< ActionPrimitivesWayPoint > &wayPoints, const std::string &handSeqKey, ActionPrimitivesCallback *clb=NULL) |
| Insert in the actions queue a combination of hand and arm trajectory in the operational space parametrized in terms of waypoints. | |
| virtual bool | pushWaitState (const double tmo, ActionPrimitivesCallback *clb=NULL) |
| Insert a wait state in the actions queue. | |
| virtual bool | reachPose (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const double execTime=ACTIONPRIM_DISABLE_EXECTIME) |
| Immediately update the current reaching target (without affecting the actions queue) or initiate a new reach (if the actions queue is empty). | |
| virtual bool | reachPosition (const yarp::sig::Vector &x, const double execTime=ACTIONPRIM_DISABLE_EXECTIME) |
| Immediately update the current reaching target (without affecting the actions queue) or initiate a new reach (if the actions queue is empty). | |
| virtual bool | clearActionsQueue () |
| Empty the actions queue. | |
| virtual bool | lockActions () |
| Disable the possibility to yield any new action. | |
| virtual bool | unlockActions () |
| Enable the possibility to yield new actions. | |
| virtual bool | getActionsLockStatus () const |
| Return the actions lock status. | |
| virtual bool | addHandSeqWP (const std::string &handSeqKey, const yarp::sig::Vector &poss, const yarp::sig::Vector &vels, const yarp::sig::Vector &tols, const yarp::sig::Vector &thres, const double tmo) |
| Define an hand WayPoint (WP) to be added at the bottom of the hand motion sequence pointed by the key. | |
| virtual bool | addHandSequence (const std::string &handSeqKey, const yarp::os::Bottle &sequence) |
| Define an hand motion sequence from a configuration bottle. | |
| virtual bool | isValidHandSeq (const std::string &handSeqKey) |
| Check whether a sequence key is defined. | |
| virtual bool | removeHandSeq (const std::string &handSeqKey) |
| Remove an already existing hand motion sequence. | |
| std::deque< std::string > | getHandSeqList () |
| Return the list of available hand sequence keys. | |
| virtual bool | getHandSequence (const std::string &handSeqKey, yarp::os::Bottle &sequence) |
| Return a hand sequence. | |
| virtual bool | areFingersMoving (bool &f) |
| Query if fingers are moving. | |
| virtual bool | areFingersInPosition (bool &f) |
| Query if fingers are in position (cumulative response). | |
| virtual bool | areFingersInPosition (std::deque< bool > &f) |
| Query if fingers are in position (finger-wise response). | |
| virtual bool | getGraspModel (perception::Model *&model) const |
| Return the model used internally to detect external contacts. | |
| virtual bool | getCartesianIF (yarp::dev::ICartesianControl *&ctrl) const |
| Return the cartesian interface used internally to control the limb. | |
| virtual bool | getTorsoJoints (yarp::sig::Vector &torso) |
| Return the control status of torso joints. | |
| virtual bool | setTorsoJoints (const yarp::sig::Vector &torso) |
| Change the control status of torso joints. | |
| virtual bool | getPose (yarp::sig::Vector &x, yarp::sig::Vector &o) const |
| Get the current arm pose. | |
| virtual bool | stopControl () |
| Stop any ongoing arm/hand movements. | |
| virtual bool | setDefaultExecTime (const double execTime) |
| Set the default arm movement execution time. | |
| virtual double | getDefaultExecTime () const |
| Get the current default arm movement execution time. | |
| virtual bool | setTrackingMode (const bool f) |
| Set the task space controller in tracking or non-tracking mode. | |
| virtual bool | getTrackingMode () const |
| Get the current controller mode. | |
| virtual bool | enableArmWaving (const yarp::sig::Vector &restPos) |
| Enable the waving mode that keeps on moving the arm around a predefined position. | |
| virtual bool | disableArmWaving () |
| Disable the waving mode. | |
| virtual bool | enableReachingTimeout (const double tmo) |
| Enable timeout while reaching. | |
| virtual bool | disableReachingTimeout () |
| Disable timeout while reaching. | |
| virtual bool | checkActionsDone (bool &f, const bool sync=false) |
| Check whether all the actions in queue are accomplished. | |
| virtual bool | checkActionOnGoing (bool &f, const bool sync=false) |
| Check whether an action is still ongoing. | |
| virtual bool | syncCheckInterrupt (const bool disable=false) |
| Suddenly interrupt any blocking call that is pending on querying the action status. | |
| virtual bool | syncCheckReinstate () |
| Reinstate the blocking feature for future calls with sync switch on. | |
Additional Inherited Members | |
Protected Member Functions inherited from iCub::action::ActionPrimitives | |
| virtual void | printMessage (const int logtype, const char *format,...) const |
| virtual bool | handleTorsoDOF (yarp::os::Property &opt, const std::string &key) |
| virtual void | disableTorsoDof () |
| virtual void | enableTorsoDof () |
| virtual bool | configHandSeq (yarp::os::Property &opt) |
| virtual bool | configGraspModel (yarp::os::Property &opt) |
| virtual bool | _pushAction (const bool execArm, const yarp::sig::Vector &x, const yarp::sig::Vector &o, const double execTime, const bool oEnabled, const bool execHand, const HandWayPoint &handWP, const bool handSeqTerminator, ActionPrimitivesCallback *clb) |
| virtual bool | _pushAction (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const std::string &handSeqKey, const double execTime, ActionPrimitivesCallback *clb, const bool oEnabled) |
| virtual bool | handCheckMotionDone (const int jnt) |
| virtual bool | wait (const Action &action) |
| virtual bool | cmdArm (const Action &action) |
| virtual bool | cmdArmWP (const Action &action) |
| virtual bool | cmdHand (const Action &action) |
| virtual bool | isHandSeqEnded () |
| virtual void | postReachCallback () |
| virtual void | init () |
| virtual bool | execQueuedAction () |
| virtual bool | execPendingHandSequences () |
| virtual void | run () |
Protected Attributes inherited from iCub::action::ActionPrimitives | |
| std::string | robot |
| std::string | local |
| std::string | part |
| yarp::dev::PolyDriver | polyHand |
| yarp::dev::PolyDriver | polyCart |
| yarp::dev::IControlMode * | modCtrl |
| yarp::dev::IEncoders * | encCtrl |
| yarp::dev::IPositionControl * | posCtrl |
| yarp::dev::ICartesianControl * | cartCtrl |
| perception::Model * | graspModel |
| yarp::os::PeriodicThread * | armWaver |
| std::mutex | mtx |
| std::mutex | mtx_motionStartEvent |
| std::condition_variable | cv_motionStartEvent |
| std::mutex | mtx_motionDoneEvent |
| std::condition_variable | cv_motionDoneEvent |
| bool | armMoveDone |
| bool | handMoveDone |
| bool | latchArmMoveDone |
| bool | latchHandMoveDone |
| bool | handSeqTerminator |
| bool | fingersInPosition |
| std::deque< bool > | fingerInPosition |
| bool | configured |
| bool | closed |
| bool | checkEnabled |
| bool | tracking_mode |
| bool | torsoActive |
| bool | reachTmoEnabled |
| bool | locked |
| bool | verbose |
| double | default_exec_time |
| double | waitTmo |
| double | reachTmo |
| double | latchTimerWait |
| double | latchTimerReach |
| double | latchTimerReachLog |
| int | jHandMin |
| int | jHandMax |
| yarp::sig::Vector | enableTorsoSw |
| yarp::sig::Vector | disableTorsoSw |
| yarp::sig::Vector | curHandFinalPoss |
| yarp::sig::Vector | curHandTols |
| yarp::sig::Vector | curGraspDetectionThres |
| double | curHandTmo |
| double | latchTimerHand |
| std::vector< int > | fingersJnts |
| std::set< int > | fingersJntsSet |
| std::set< int > | fingersMovingJntsSet |
| std::multimap< int, int > | fingers2JntsMap |
| ActionPrimitivesCallback * | actionClb |
| yarp::os::PeriodicThread * | actionWP |
| iCub::action::ActionPrimitives::ActionsQueue | actionsQueue |
| std::map< std::string, std::deque< HandWayPoint > > | handSeqMap |
A derived class defining a first abstraction layer on top of actionPrimitives father class.
It internally predeclares (without actually defining) a set of hand sequence motions key ("open_hand", "close_hand" and "karate_hand" :) that are used for grasp(), touch() and tap() actions.
Definition at line 930 of file actionPrimitives.h.
|
inline |
Default Constructor.
Definition at line 936 of file actionPrimitives.h.
|
inline |
Constructor.
| opt | the Property used to configure the object after its creation. |
Definition at line 943 of file actionPrimitives.h.
|
virtual |
Grasp the given target (combined action).
| x | the 3-d target position [m]. |
| o | the 4-d hand orientation used while reaching/grasping (given in axis-angle representation: ax ay az angle in rad). |
| d | the displacement [m] wrt the target position that identifies a location to be reached prior to grasping. |
It reachs for (x+d,o) opening the hand, then reachs for (x,o) and finally closes the hand.
Reimplemented in iCub::action::ActionPrimitivesLayer2.
Definition at line 2073 of file actionPrimitives.cpp.
|
virtual |
Tap the given target (combined action).
| x1 | the fisrt 3-d target position [m]. |
| o1 | the first 4-d hand orientation (given in axis-angle representation: ax ay az angle in rad). |
| x2 | the second 3-d target position [m]. |
| o2 | the second 4-d hand orientation (given in axis-angle representation: ax ay az angle in rad). |
| execTime | the arm action execution time only while tapping [s] (to be specified iff different from default value). |
It reachs for (x1,o1), then reachs for (x2,o2) and then again for (x1,o1).
Definition at line 2108 of file actionPrimitives.cpp.
|
virtual |
Touch the given target (combined action).
| x | the 3-d target position [m]. |
| o | the 4-d hand orientation used while reaching/touching (given in axis-angle representation: ax ay az angle in rad). |
| d | the displacement [m] wrt the target position that identifies a location to be reached prior to touching. |
It reachs for (x+d,o), then reachs for (x,o). Similar to grasp but without final hand action.
Reimplemented in iCub::action::ActionPrimitivesLayer2.
Definition at line 2091 of file actionPrimitives.cpp.