#include <ikfast_moveit_state_adapter.h>
Public Member Functions | |
virtual bool | getAllIK (const Eigen::Affine3d &pose, std::vector< std::vector< double > > &joint_poses) 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 |
virtual bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &world_frame, const std::string &tcp_frame) |
void | setState (const moveit::core::RobotState &state) |
Sets the internal state of the robot model to the argument. For the IKFast impl, it also recomputes the transformations to/from the IKFast reference frames. | |
virtual | ~IkFastMoveitStateAdapter () |
Protected Member Functions | |
bool | computeIKFastTransforms () |
Protected Attributes | |
descartes_core::Frame | tool0_to_tip_ |
descartes_core::Frame | world_to_base_ |
Definition at line 26 of file ikfast_moveit_state_adapter.h.
virtual descartes_moveit::IkFastMoveitStateAdapter::~IkFastMoveitStateAdapter | ( | ) | [inline, virtual] |
Definition at line 29 of file ikfast_moveit_state_adapter.h.
bool descartes_moveit::IkFastMoveitStateAdapter::computeIKFastTransforms | ( | ) | [protected] |
Definition at line 138 of file ikfast_moveit_state_adapter.cpp.
bool descartes_moveit::IkFastMoveitStateAdapter::getAllIK | ( | const Eigen::Affine3d & | pose, |
std::vector< std::vector< double > > & | joint_poses | ||
) | const [virtual] |
Reimplemented from descartes_moveit::MoveitStateAdapter.
Definition at line 67 of file ikfast_moveit_state_adapter.cpp.
bool descartes_moveit::IkFastMoveitStateAdapter::getFK | ( | const std::vector< double > & | joint_pose, |
Eigen::Affine3d & | pose | ||
) | const [virtual] |
Reimplemented from descartes_moveit::MoveitStateAdapter.
Definition at line 113 of file ikfast_moveit_state_adapter.cpp.
bool descartes_moveit::IkFastMoveitStateAdapter::getIK | ( | const Eigen::Affine3d & | pose, |
const std::vector< double > & | seed_state, | ||
std::vector< double > & | joint_pose | ||
) | const [virtual] |
Reimplemented from descartes_moveit::MoveitStateAdapter.
Definition at line 100 of file ikfast_moveit_state_adapter.cpp.
bool descartes_moveit::IkFastMoveitStateAdapter::initialize | ( | const std::string & | robot_description, |
const std::string & | group_name, | ||
const std::string & | world_frame, | ||
const std::string & | tcp_frame | ||
) | [virtual] |
Reimplemented from descartes_moveit::MoveitStateAdapter.
Definition at line 54 of file ikfast_moveit_state_adapter.cpp.
void descartes_moveit::IkFastMoveitStateAdapter::setState | ( | const moveit::core::RobotState & | state | ) |
Sets the internal state of the robot model to the argument. For the IKFast impl, it also recomputes the transformations to/from the IKFast reference frames.
Reimplemented from descartes_moveit::MoveitStateAdapter.
Definition at line 132 of file ikfast_moveit_state_adapter.cpp.
The IKFast implementation commonly solves between 'base_link' of a robot and 'tool0'. We will commonly want to take advantage of an additional fixed transformation from the robot flange, 'tool0', to some user defined tool. This prevents the user from having to manually adjust tool poses to account for this.
Definition at line 59 of file ikfast_moveit_state_adapter.h.
Likewise this parameter is used to accomodate transformations between the base of the IKFast solver and the base of the MoveIt move group.
Definition at line 65 of file ikfast_moveit_state_adapter.h.