HandPlugin Class Reference

#include <HandPlugin.hh>

Public Member Functions

 HandPlugin ()
 Constructs the object. More...
 
virtual ~HandPlugin ()
 Destroys the object. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Loads the plugin. More...
 
void onUpdate ()
 Updates model on world update. More...
 
void onReset ()
 Updates model on world reset. More...
 
void onRequest (HandMsgPtr &_msg)
 Callback function for handling incoming requests. More...
 

Private Member Functions

bool loadMimicJoints (sdf::ElementPtr _sdf, JointGroup &joint)
 TODO. More...
 
bool loadJointGroups (sdf::ElementPtr _sdf)
 Loads finger joints. More...
 
bool loadVirtualJoints (sdf::ElementPtr _sdf)
 Loads virtual joints. More...
 
bool loadControllers (sdf::ElementPtr _sdf)
 Loads PID controllers for each joint. More...
 
void imobilise ()
 Imobilises the hand. More...
 
void resetJoints ()
 Resets finger joints to default pose. More...
 
void setupTimer (common::Time &timeout, bool &trigger, const common::Time &duration)
 Sets up a timer routine. More...
 
void setPose (const ignition::math::Pose3d &pose)
 Changes hand's pose. More...
 
void updatePose (HandMsgPtr &_msg)
 Changes hand's pose on request. More...
 
void updateTimer (HandMsgPtr &_msg)
 Updates internal timer. More...
 
void updateForces ()
 Updates joints by applying forces directly. More...
 
void setPIDController (physics::JointControllerPtr controller, int type, physics::JointPtr joint, double p, double i, double d, double initial_value)
 
void setPIDTarget (int type, physics::JointPtr joint, double value, bool force=false)
 Change PID target. More...
 
void updatePIDTargets (HandMsgPtr &_msg)
 Changes hand's pid controller targets. More...
 
void checkReset (HandMsgPtr &_msg)
 Resets world on request. More...
 
void sendTimeout ()
 Broadcasts a timeout message. More...
 
void resetWorld ()
 Resets the world. More...
 

Private Attributes

std::unique_ptr< HandPluginPrivatedata_ptr
 Class with private attributes. More...
 
physics::ModelPtr model
 Model to which the plugin is attached. More...
 
physics::WorldPtr world
 World in which the model exists. More...
 
event::ConnectionPtr update_connection
 Connection to world update event. More...
 
event::ConnectionPtr reset_connection
 Connection to world reset event. More...
 
std::vector< JointGroupjoint_groups
 Array of finger joints. More...
 
std::vector< physics::JointPtr > virtual_joints
 Array of virtual x y z r p y joint pointers. More...
 
bool timer_active {false}
 Timeout trigger. More...
 
common::Time timeout
 Next timeout. More...
 
const common::Time routine_timestep {0.02}
 Routine update time step in seconds. More...
 
bool routine_active {false}
 Periodic timer trigger. More...
 
common::Time routine_timeout
 Next routine timeout. More...
 
std::vector< JointForcePairjoint_force_pairs
 Array of finger joints. More...
 
ignition::math::Pose3d init_pose {0,0,1,0,0,0}
 Initial pose. More...
 
bool recv_msg {false}
 Flag for message received. More...
 
boost::shared_ptr< HandMsg const > msg_req
 Last received request message. More...
 

Constructor & Destructor Documentation

Constructs the object.

~HandPlugin ( )
virtual

Destroys the object.

Member Function Documentation

void checkReset ( HandMsgPtr _msg)
private

Resets world on request.

Parameters
_msgThe request message
void imobilise ( )
private

Imobilises the hand.

void Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Loads the plugin.

Parameters
_modelThe model pointer
_sdfThe sdf element pointer
bool loadControllers ( sdf::ElementPtr  _sdf)
private

Loads PID controllers for each joint.

Parameters
_sdfThe root sdf element pointer
Returns
Success
bool loadJointGroups ( sdf::ElementPtr  _sdf)
private

Loads finger joints.

Parameters
_sdfThe root sdf element pointer
Returns
Success
bool loadMimicJoints ( sdf::ElementPtr  _sdf,
JointGroup joint 
)
private

TODO.

bool loadVirtualJoints ( sdf::ElementPtr  _sdf)
private

Loads virtual joints.

Parameters
_sdfThe root sdf element pointer
Returns
Success
void onRequest ( HandMsgPtr _msg)

Callback function for handling incoming requests.

Parameters
_msgThe message
void onReset ( )

Updates model on world reset.

void onUpdate ( )

Updates model on world update.

void resetJoints ( )
private

Resets finger joints to default pose.

void resetWorld ( )
private

Resets the world.

void sendTimeout ( )
private

Broadcasts a timeout message.

void setPIDController ( physics::JointControllerPtr  controller,
int  type,
physics::JointPtr  joint,
double  p,
double  i,
double  d,
double  initial_value 
)
private
void setPIDTarget ( int  type,
physics::JointPtr  joint,
double  value,
bool  force = false 
)
private

Change PID target.

Parameters
typeType of PID control
jointScoped name of controlled joint
valueDesired target value
forceForce joint position to target value
void setPose ( const ignition::math::Pose3d &  pose)
private

Changes hand's pose.

Since the hand is fixed to the world, the pose can not be set directly, and instead must be obtained using the virtual joints.

Parameters
poseThe new pose
void setupTimer ( common::Time &  timeout,
bool &  trigger,
const common::Time &  duration 
)
private

Sets up a timer routine.

Parameters
timeoutTimeout to be checked in main onUpdate routine
triggerBoolean switch that indicates timer is active
durationTime until next timeout
void updateForces ( )
private

Updates joints by applying forces directly.

void updatePIDTargets ( HandMsgPtr _msg)
private

Changes hand's pid controller targets.

Parameters
_msgThe request message
void updatePose ( HandMsgPtr _msg)
private

Changes hand's pose on request.

Parameters
_msgThe request message
void updateTimer ( HandMsgPtr _msg)
private

Updates internal timer.

Parameters
_msgThe request message

Member Data Documentation

std::unique_ptr<HandPluginPrivate> data_ptr
private

Class with private attributes.

ignition::math::Pose3d init_pose {0,0,1,0,0,0}
private

Initial pose.

std::vector<JointForcePair> joint_force_pairs
private

Array of finger joints.

std::vector<JointGroup> joint_groups
private

Array of finger joints.

physics::ModelPtr model
private

Model to which the plugin is attached.

boost::shared_ptr<HandMsg const> msg_req
private

Last received request message.

bool recv_msg {false}
private

Flag for message received.

event::ConnectionPtr reset_connection
private

Connection to world reset event.

bool routine_active {false}
private

Periodic timer trigger.

common::Time routine_timeout
private

Next routine timeout.

const common::Time routine_timestep {0.02}
private

Routine update time step in seconds.

common::Time timeout
private

Next timeout.

bool timer_active {false}
private

Timeout trigger.

event::ConnectionPtr update_connection
private

Connection to world update event.

std::vector<physics::JointPtr> virtual_joints
private

Array of virtual x y z r p y joint pointers.

physics::WorldPtr world
private

World in which the model exists.


The documentation for this class was generated from the following files: