Public Member Functions | Protected Member Functions | Protected Attributes
descartes_core::RobotModel Class Reference

RobotModel defines the interface to a kinematics/dynamics functions. Implementations of this class will be used in conjunction with TrajectoryPt objects to determine forward and inverse kinematics. More...

#include <robot_model.h>

List of all members.

Public Member Functions

virtual bool getAllIK (const Eigen::Affine3d &pose, std::vector< std::vector< double > > &joint_poses) const =0
 Returns "all" the joint poses("distributed" in joint space) for a desired affine pose. "All" is determined by each implementation (In the worst case, this means at least getIK). "Distributed" is determined by each implementation.
virtual bool getCheckCollisions ()
 Indicates if collision checks are enabled.
virtual int getDOF () const =0
 Returns number of DOFs.
virtual bool getFK (const std::vector< double > &joint_pose, Eigen::Affine3d &pose) const =0
 Returns the affine pose.
virtual bool getIK (const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const =0
 Returns the joint pose closest to the seed pose for a desired affine pose.
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &world_frame, const std::string &tcp_frame)=0
 Initializes the robot model when it is instantiated as a moveit_core plugin.
virtual bool isValid (const std::vector< double > &joint_pose) const =0
 Performs all necessary checks to determine joint pose is valid.
virtual bool isValid (const Eigen::Affine3d &pose) const =0
 Performs all necessary checks to determine affine pose is valid.
virtual bool isValidMove (const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const =0
 Performs necessary checks to see if the robot is capable of moving from the initial joint pose to the final pose in dt seconds.
virtual void setCheckCollisions (bool check_collisions)
 Enables collision checks.
virtual ~RobotModel ()

Protected Member Functions

 RobotModel ()

Protected Attributes

bool check_collisions_

Detailed Description

RobotModel defines the interface to a kinematics/dynamics functions. Implementations of this class will be used in conjunction with TrajectoryPt objects to determine forward and inverse kinematics.

All methods in this interface class assume a *FIXED* TOOL & WOBJ frame (see TrajectoryPt for frame definitions). The methods for setting/getting these frames are not defined by this class. Implementations of this interface should provide these either by construction or getter/setter methods.

Definition at line 40 of file robot_model.h.


Constructor & Destructor Documentation

virtual descartes_core::RobotModel::~RobotModel ( ) [inline, virtual]

Definition at line 44 of file robot_model.h.

descartes_core::RobotModel::RobotModel ( ) [inline, protected]

Definition at line 136 of file robot_model.h.


Member Function Documentation

virtual bool descartes_core::RobotModel::getAllIK ( const Eigen::Affine3d &  pose,
std::vector< std::vector< double > > &  joint_poses 
) const [pure virtual]

Returns "all" the joint poses("distributed" in joint space) for a desired affine pose. "All" is determined by each implementation (In the worst case, this means at least getIK). "Distributed" is determined by each implementation.

Parameters:
poseAffine pose of TOOL in WOBJ frame
joint_posesSolution (if function successful).
Returns:
True if successful
virtual bool descartes_core::RobotModel::getCheckCollisions ( ) [inline, virtual]

Indicates if collision checks are enabled.

Returns:
Bool

Definition at line 118 of file robot_model.h.

virtual int descartes_core::RobotModel::getDOF ( ) const [pure virtual]

Returns number of DOFs.

Returns:
Int
virtual bool descartes_core::RobotModel::getFK ( const std::vector< double > &  joint_pose,
Eigen::Affine3d &  pose 
) const [pure virtual]

Returns the affine pose.

Parameters:
joint_poseSolution (if function successful).
poseAffine pose of TOOL in WOBJ frame
Returns:
True if successful
virtual bool descartes_core::RobotModel::getIK ( const Eigen::Affine3d &  pose,
const std::vector< double > &  seed_state,
std::vector< double > &  joint_pose 
) const [pure virtual]

Returns the joint pose closest to the seed pose for a desired affine pose.

Parameters:
poseAffine pose of TOOL in WOBJ frame
seed_stateJoint position seed (returned solution is "close" to the seed).
joint_poseSolution (if function successful).
Returns:
True if successful
virtual bool descartes_core::RobotModel::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  world_frame,
const std::string &  tcp_frame 
) [pure virtual]

Initializes the robot model when it is instantiated as a moveit_core plugin.

Parameters:
robot_descriptionname of the ros parameter containing the urdf description
group_namethe manipulation group for all the robot links that are part of the same kinematic chain
world_framename of the root link in the urdf
tcp_frametool link attached to the robot. When it's not in 'group_name' then it should have a fixed location relative to the last link in 'group_name'.
virtual bool descartes_core::RobotModel::isValid ( const std::vector< double > &  joint_pose) const [pure virtual]

Performs all necessary checks to determine joint pose is valid.

Parameters:
joint_posePose to check
Returns:
True if valid
virtual bool descartes_core::RobotModel::isValid ( const Eigen::Affine3d &  pose) const [pure virtual]

Performs all necessary checks to determine affine pose is valid.

Parameters:
poseAffine pose of TOOL in WOBJ frame
Returns:
True if valid
virtual bool descartes_core::RobotModel::isValidMove ( const std::vector< double > &  from_joint_pose,
const std::vector< double > &  to_joint_pose,
double  dt 
) const [pure virtual]

Performs necessary checks to see if the robot is capable of moving from the initial joint pose to the final pose in dt seconds.

Parameters:
from_joint_pose[description]
to_joint_pose[description]
dt[description]
Returns:
[description]
virtual void descartes_core::RobotModel::setCheckCollisions ( bool  check_collisions) [inline, virtual]

Enables collision checks.

Parameters:
check_collisionsenables or disables collisions

Definition at line 109 of file robot_model.h.


Member Data Documentation

Definition at line 138 of file robot_model.h.


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


descartes_core
Author(s): Dan Solomon
autogenerated on Wed Aug 26 2015 11:21:21