#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< HandPluginPrivate > | data_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< JointGroup > | joint_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< JointForcePair > | joint_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... | |
| HandPlugin | ( | ) |
Constructs the object.
|
virtual |
Destroys the object.
|
private |
Resets world on request.
| _msg | The request message |
|
private |
Imobilises the hand.
|
virtual |
Loads the plugin.
| _model | The model pointer |
| _sdf | The sdf element pointer |
|
private |
Loads PID controllers for each joint.
| _sdf | The root sdf element pointer |
|
private |
Loads finger joints.
| _sdf | The root sdf element pointer |
|
private |
TODO.
|
private |
Loads virtual joints.
| _sdf | The root sdf element pointer |
| void onRequest | ( | HandMsgPtr & | _msg | ) |
Callback function for handling incoming requests.
| _msg | The message |
| void onReset | ( | ) |
Updates model on world reset.
| void onUpdate | ( | ) |
Updates model on world update.
|
private |
Resets finger joints to default pose.
|
private |
Resets the world.
|
private |
Broadcasts a timeout message.
|
private |
|
private |
Change PID target.
| type | Type of PID control |
| joint | Scoped name of controlled joint |
| value | Desired target value |
| force | Force joint position to target value |
|
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.
| pose | The new pose |
|
private |
Sets up a timer routine.
| timeout | Timeout to be checked in main onUpdate routine |
| trigger | Boolean switch that indicates timer is active |
| duration | Time until next timeout |
|
private |
Updates joints by applying forces directly.
|
private |
Changes hand's pid controller targets.
| _msg | The request message |
|
private |
Changes hand's pose on request.
| _msg | The request message |
|
private |
Updates internal timer.
| _msg | The request message |
|
private |
Class with private attributes.
|
private |
Initial pose.
|
private |
Array of finger joints.
|
private |
Array of finger joints.
|
private |
Model to which the plugin is attached.
|
private |
Last received request message.
|
private |
Flag for message received.
|
private |
Connection to world reset event.
|
private |
Periodic timer trigger.
|
private |
Next routine timeout.
|
private |
Routine update time step in seconds.
|
private |
Next timeout.
|
private |
Timeout trigger.
|
private |
Connection to world update event.
|
private |
Array of virtual x y z r p y joint pointers.
|
private |
World in which the model exists.