$search
A state trasformer that uses forward and inverse kinematics to convert to and from ompl and physical robot states. More...
#include <ompl_ros_ik_state_transformer.h>
Public Member Functions | |
virtual bool | configureOnRequest (const arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)=0 |
Configure the transformer when a request is received. This is typically a one time configuration for each planning request. | |
virtual bool | forwardTransform (const arm_navigation_msgs::RobotState &robot_state, ompl::base::State &ompl_state)=0 |
Compute the forward transform (from physical state to planning state). | |
virtual arm_navigation_msgs::RobotState | getDefaultState ()=0 |
Get a default physical state. | |
virtual std::string | getFrame () |
Get the frame in which the kinematics solver is operating. | |
virtual bool | initialize ()=0 |
Custom initialization can be performed here. | |
virtual bool | inverseTransform (const ompl::base::State &ompl_state, arm_navigation_msgs::RobotState &robot_state)=0 |
Compute the inverse transform (from planning state to physical state). | |
OmplRosIKStateTransformer (const ompl::base::StateSpacePtr &state_space, const planning_models::KinematicModel::JointModelGroup *physical_joint_model_group) | |
Default constructor. | |
~OmplRosIKStateTransformer () | |
Protected Attributes | |
kinematics::KinematicsBase * | kinematics_solver_ |
Private Attributes | |
std::string | group_name_ |
pluginlib::ClassLoader < kinematics::KinematicsBase > | kinematics_loader_ |
std::string | physical_group_name_ |
A state trasformer that uses forward and inverse kinematics to convert to and from ompl and physical robot states.
Definition at line 54 of file ompl_ros_ik_state_transformer.h.
ompl_ros_interface::OmplRosIKStateTransformer::OmplRosIKStateTransformer | ( | const ompl::base::StateSpacePtr & | state_space, | |
const planning_models::KinematicModel::JointModelGroup * | physical_joint_model_group | |||
) |
Default constructor.
state_space | - The state space that the planner is operating on | |
physical_joint_model_group | - The "physical" joint model group that the planner is operating on |
Definition at line 41 of file ompl_ros_ik_state_transformer.cpp.
ompl_ros_interface::OmplRosIKStateTransformer::~OmplRosIKStateTransformer | ( | ) | [inline] |
Definition at line 64 of file ompl_ros_ik_state_transformer.h.
virtual bool ompl_ros_interface::OmplRosIKStateTransformer::configureOnRequest | ( | const arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) | [pure virtual] |
Configure the transformer when a request is received. This is typically a one time configuration for each planning request.
Implements ompl_ros_interface::OmplRosStateTransformer.
Implemented in ompl_ros_interface::OmplRosRPYIKStateTransformer.
virtual bool ompl_ros_interface::OmplRosIKStateTransformer::forwardTransform | ( | const arm_navigation_msgs::RobotState & | robot_state, | |
ompl::base::State & | ompl_state | |||
) | [pure virtual] |
Compute the forward transform (from physical state to planning state).
Implements ompl_ros_interface::OmplRosStateTransformer.
Implemented in ompl_ros_interface::OmplRosRPYIKStateTransformer.
virtual arm_navigation_msgs::RobotState ompl_ros_interface::OmplRosIKStateTransformer::getDefaultState | ( | ) | [pure virtual] |
Get a default physical state.
Implements ompl_ros_interface::OmplRosStateTransformer.
Implemented in ompl_ros_interface::OmplRosRPYIKStateTransformer.
virtual std::string ompl_ros_interface::OmplRosIKStateTransformer::getFrame | ( | ) | [inline, virtual] |
Get the frame in which the kinematics solver is operating.
Reimplemented from ompl_ros_interface::OmplRosStateTransformer.
Definition at line 92 of file ompl_ros_ik_state_transformer.h.
virtual bool ompl_ros_interface::OmplRosIKStateTransformer::initialize | ( | ) | [pure virtual] |
Custom initialization can be performed here.
Implements ompl_ros_interface::OmplRosStateTransformer.
Implemented in ompl_ros_interface::OmplRosRPYIKStateTransformer.
virtual bool ompl_ros_interface::OmplRosIKStateTransformer::inverseTransform | ( | const ompl::base::State & | ompl_state, | |
arm_navigation_msgs::RobotState & | robot_state | |||
) | [pure virtual] |
Compute the inverse transform (from planning state to physical state).
ompl_state | - the planning state | |
robot_State | - the corresponding physical state |
Implements ompl_ros_interface::OmplRosStateTransformer.
Implemented in ompl_ros_interface::OmplRosRPYIKStateTransformer.
std::string ompl_ros_interface::OmplRosIKStateTransformer::group_name_ [private] |
Definition at line 109 of file ompl_ros_ik_state_transformer.h.
pluginlib::ClassLoader<kinematics::KinematicsBase> ompl_ros_interface::OmplRosIKStateTransformer::kinematics_loader_ [private] |
Definition at line 111 of file ompl_ros_ik_state_transformer.h.
kinematics::KinematicsBase* ompl_ros_interface::OmplRosIKStateTransformer::kinematics_solver_ [protected] |
Definition at line 106 of file ompl_ros_ik_state_transformer.h.
std::string ompl_ros_interface::OmplRosIKStateTransformer::physical_group_name_ [private] |
Definition at line 110 of file ompl_ros_ik_state_transformer.h.