Flat Object Grasping Library (FOG)  0.2.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
fog::Interface Class Referenceabstract

Abstract class which defines the interfaces with FOG. More...

#include <fog/interface.h>

+ Collaboration diagram for fog::Interface:

Public Member Functions

 Interface ()
 
 Interface (const std::shared_ptr< arl::robot::Robot > &the_arm, const std::shared_ptr< arl::robot::Robot > &the_hand, const std::shared_ptr< arl::robot::Sensor > &sensor, const std::shared_ptr< arl::viz::RosStatePublisher > &the_viz)
 
virtual void getParameters ()=0
 Reads the parameters for FOG. More...
 
virtual PointCloud getObjectPointCloud ()=0
 Returns the point cloud of the object. More...
 
virtual std::vector< Point3getSurfaceEdges ()=0
 Returns the eges of the support surface. More...
 
virtual void reachIGS (const fog::InitialGraspState &igs)=0
 Communicates with the robot in order to reach and IGS. More...
 
virtual bool planIGS (fog::InitialGraspState &igs)=0
 Interfacing with an external planner for planning an IGS. More...
 
virtual void robotGoHome ()=0
 Sends the robot to the home configuration. More...
 
virtual Pose getTipPalmTransform (const Eigen::VectorXd &joint_states)=0
 Reads the tranformation for the tip of the hand to the palm of the hand. More...
 
virtual void setHandConfiguration (const Eigen::VectorXd &joint_states, double duration=5.0, bool blocking=true)=0
 Communicates with the hand for reaching a hand configuration/preshape. More...
 
virtual fog::Pose getTransformationFromPalm (fog::FrameLabel frame, const Eigen::VectorXd &joint_states)=0
 Provides the transformation of the given frame w.r.t. the palm (or the base of the hand). More...
 

Public Attributes

std::shared_ptr
< arl::robot::Robot > 
arm
 
std::shared_ptr
< arl::robot::Robot > 
hand
 
std::shared_ptr
< arl::robot::Sensor > 
ft_sensor
 
std::shared_ptr
< arl::viz::RosStatePublisher > 
viz
 
Params params
 The FOG params in order to be available to the components of the library. More...
 

Detailed Description

Abstract class which defines the interfaces with FOG.

You can inherit and implement this class in order to define your own interfaces with the rest of the world.

Constructor & Destructor Documentation

fog::Interface::Interface ( )
inline
fog::Interface::Interface ( const std::shared_ptr< arl::robot::Robot > &  the_arm,
const std::shared_ptr< arl::robot::Robot > &  the_hand,
const std::shared_ptr< arl::robot::Sensor > &  sensor,
const std::shared_ptr< arl::viz::RosStatePublisher > &  the_viz 
)
inline

Member Function Documentation

virtual PointCloud fog::Interface::getObjectPointCloud ( )
pure virtual

Returns the point cloud of the object.

There are multiple ways to implement this. For example you can read the point cloud from a file or from a ROS topic.

Returns
The object's point cloud
virtual void fog::Interface::getParameters ( )
pure virtual

Reads the parameters for FOG.

Writes the parameters to the fog::Interface::params

See Also
fog::Params
virtual std::vector<Point3> fog::Interface::getSurfaceEdges ( )
pure virtual

Returns the eges of the support surface.

Returns
The edges of the support surface.
virtual Pose fog::Interface::getTipPalmTransform ( const Eigen::VectorXd &  joint_states)
pure virtual

Reads the tranformation for the tip of the hand to the palm of the hand.

Parameters
joint_statesThe desired joint position for finding the forward kinematics of the fingertip.
virtual fog::Pose fog::Interface::getTransformationFromPalm ( fog::FrameLabel  frame,
const Eigen::VectorXd &  joint_states 
)
pure virtual

Provides the transformation of the given frame w.r.t. the palm (or the base of the hand).

Parameters
frameThe frame to find its transformation from the palm frame.
joint_statesThe joint positions of the fingers in order to solve the F/K.
Returns
The trasformation
virtual bool fog::Interface::planIGS ( fog::InitialGraspState igs)
pure virtual

Interfacing with an external planner for planning an IGS.

You can use any planner you want, for example MoveIt!.

Parameters
igsThe IGS to be planned. If the planner found a plan for the given IGS this function should write the solution on the fog::InitialGraspState::joint_trajectory_solution
Returns
True if a solution was found, false eitherwise.
virtual void fog::Interface::reachIGS ( const fog::InitialGraspState igs)
pure virtual

Communicates with the robot in order to reach and IGS.

You have to send to the robot the joint trajectory solution of the IGS.

Parameters
TheIGS to be reached.
virtual void fog::Interface::robotGoHome ( )
pure virtual

Sends the robot to the home configuration.

virtual void fog::Interface::setHandConfiguration ( const Eigen::VectorXd &  joint_states,
double  duration = 5.0,
bool  blocking = true 
)
pure virtual

Communicates with the hand for reaching a hand configuration/preshape.

It reads the current configuration of the hand and sends a joint trajectory to the finger joints.

Parameters
joint_statesThe desired final joint states of the preshape.
durationThe duration of the joint trajectory
blockingTrue if the program should wait for the fingertips to reach the final joint configuration. False otherwise.

Member Data Documentation

std::shared_ptr<arl::robot::Robot> fog::Interface::arm
std::shared_ptr<arl::robot::Sensor> fog::Interface::ft_sensor
std::shared_ptr<arl::robot::Robot> fog::Interface::hand
Params fog::Interface::params

The FOG params in order to be available to the components of the library.

std::shared_ptr<arl::viz::RosStatePublisher> fog::Interface::viz