Public Member Functions | Protected Member Functions | Protected Attributes
descartes_moveit::MoveitStateAdapter Class Reference

MoveitStateAdapter adapts the MoveIt RobotState to the Descartes RobotModel interface. More...

#include <moveit_state_adapter.h>

Inheritance diagram for descartes_moveit::MoveitStateAdapter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool getAllIK (const Eigen::Affine3d &pose, std::vector< std::vector< double > > &joint_poses) const
virtual int getDOF () const
virtual bool getFK (const std::vector< double > &joint_pose, Eigen::Affine3d &pose) const
virtual bool getIK (const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const
const std::vector< std::vector
< double > > & 
getSeedStates () const
 Retrieves the initial seed states used by iterative inverse kinematic solvers.
moveit::core::RobotStatePtr getState ()
 Returns the underlying moveit state object so it can be used to generate seeds.
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &world_frame, const std::string &tcp_frame)
virtual bool isValid (const std::vector< double > &joint_pose) const
virtual bool isValid (const Eigen::Affine3d &pose) const
virtual bool isValidMove (const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const
 MoveitStateAdapter ()
 MoveitStateAdapter (const moveit::core::RobotState &robot_state, const std::string &group_name, const std::string &tool_frame, const std::string &world_frame)
void setSeedStates (const std::vector< std::vector< double > > &seeds)
 Set the initial states used for iterative inverse kineamtics.
virtual ~MoveitStateAdapter ()

Protected Member Functions

bool getIK (const Eigen::Affine3d &pose, std::vector< double > &joint_pose) const
bool isInCollision (const std::vector< double > &joint_pose) const
 Pointer to moveit robot state (mutable object state is reset with each function call.

Protected Attributes

std::string group_name_
 Planning group name.
planning_scene::PlanningScenePtr planning_scene_
robot_model_loader::RobotModelLoaderPtr robot_model_loader_
robot_model::RobotModelConstPtr robot_model_ptr_
moveit::core::RobotStatePtr robot_state_
std::vector< std::vector
< double > > 
seed_states_
 Vector of starting configurations for the numerical solver.
std::string tool_frame_
 Tool frame name.
std::vector< double > velocity_limits_
std::string world_frame_
 Work object/reference frame name.
descartes_core::Frame world_to_root_
 convenient transformation frame

Detailed Description

MoveitStateAdapter adapts the MoveIt RobotState to the Descartes RobotModel interface.

Definition at line 36 of file moveit_state_adapter.h.


Constructor & Destructor Documentation

Definition at line 65 of file moveit_state_adapter.cpp.

descartes_moveit::MoveitStateAdapter::MoveitStateAdapter ( const moveit::core::RobotState robot_state,
const std::string &  group_name,
const std::string &  tool_frame,
const std::string &  world_frame 
)

Constructor for Moveit state adapters (implements Descartes robot model interface)

Parameters:
robot_staterobot state object utilized for kinematic/dynamic state checking
group_nameplanning group name
tool_frametool frame name
world_framework object frame name

Definition at line 68 of file moveit_state_adapter.cpp.

Definition at line 53 of file moveit_state_adapter.h.


Member Function Documentation

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

Implements descartes_core::RobotModel.

Definition at line 210 of file moveit_state_adapter.cpp.

Implements descartes_core::RobotModel.

Definition at line 361 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::getFK ( const std::vector< double > &  joint_pose,
Eigen::Affine3d &  pose 
) const [virtual]

Implements descartes_core::RobotModel.

Definition at line 284 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::getIK ( const Eigen::Affine3d &  pose,
const std::vector< double > &  seed_state,
std::vector< double > &  joint_pose 
) const [virtual]

Implements descartes_core::RobotModel.

Definition at line 174 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::getIK ( const Eigen::Affine3d &  pose,
std::vector< double > &  joint_pose 
) const [protected]

Gets IK solution (assumes robot state is pre-seeded)

Parameters:
poseAffine pose of TOOL in WOBJ frame
joint_poseSolution (if function successful).
Returns:

Definition at line 181 of file moveit_state_adapter.cpp.

const std::vector<std::vector<double> >& descartes_moveit::MoveitStateAdapter::getSeedStates ( ) const [inline]

Retrieves the initial seed states used by iterative inverse kinematic solvers.

Definition at line 86 of file moveit_state_adapter.h.

moveit::core::RobotStatePtr descartes_moveit::MoveitStateAdapter::getState ( ) [inline]

Returns the underlying moveit state object so it can be used to generate seeds.

Definition at line 94 of file moveit_state_adapter.h.

bool descartes_moveit::MoveitStateAdapter::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  world_frame,
const std::string &  tcp_frame 
) [virtual]

Implements descartes_core::RobotModel.

Definition at line 118 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::isInCollision ( const std::vector< double > &  joint_pose) const [protected]

Pointer to moveit robot state (mutable object state is reset with each function call.

TODO: Checks for collisions at this joint pose. The setCollisionCheck(true) must have been called previously in order to enable collision checks, otherwise it will return false.

Parameters:
joint_posethe joint values at which check for collisions will be made

Definition at line 273 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::isValid ( const std::vector< double > &  joint_pose) const [virtual]

Implements descartes_core::RobotModel.

Definition at line 314 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::isValid ( const Eigen::Affine3d &  pose) const [virtual]

Implements descartes_core::RobotModel.

Definition at line 354 of file moveit_state_adapter.cpp.

bool descartes_moveit::MoveitStateAdapter::isValidMove ( const std::vector< double > &  from_joint_pose,
const std::vector< double > &  to_joint_pose,
double  dt 
) const [virtual]

Implements descartes_core::RobotModel.

Definition at line 368 of file moveit_state_adapter.cpp.

void descartes_moveit::MoveitStateAdapter::setSeedStates ( const std::vector< std::vector< double > > &  seeds) [inline]

Set the initial states used for iterative inverse kineamtics.

Parameters:
seedsVector of vector of doubles representing joint positions. Be sure that it's sized correctly for the DOF.

Definition at line 78 of file moveit_state_adapter.h.


Member Data Documentation

Planning group name.

Definition at line 139 of file moveit_state_adapter.h.

Definition at line 127 of file moveit_state_adapter.h.

Definition at line 128 of file moveit_state_adapter.h.

robot_model::RobotModelConstPtr descartes_moveit::MoveitStateAdapter::robot_model_ptr_ [protected]

Definition at line 129 of file moveit_state_adapter.h.

moveit::core::RobotStatePtr descartes_moveit::MoveitStateAdapter::robot_state_ [mutable, protected]

Definition at line 126 of file moveit_state_adapter.h.

std::vector<std::vector<double> > descartes_moveit::MoveitStateAdapter::seed_states_ [protected]

Vector of starting configurations for the numerical solver.

Definition at line 134 of file moveit_state_adapter.h.

Tool frame name.

Definition at line 144 of file moveit_state_adapter.h.

Definition at line 125 of file moveit_state_adapter.h.

Work object/reference frame name.

Definition at line 149 of file moveit_state_adapter.h.

convenient transformation frame

Definition at line 154 of file moveit_state_adapter.h.


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


descartes_moveit
Author(s): Shaun Edwards
autogenerated on Wed Aug 26 2015 11:21:41