Public Member Functions | Public Attributes
constrained_ik::SolverState Struct Reference

Internal state of Constrained_IK solver. More...

#include <solver_state.h>

List of all members.

Public Member Functions

void reset (const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed)
 Reset the current state to default state.
 SolverState (const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed)
 SolverState Constructor.

Public Attributes

bool auxiliary_at_limit
double auxiliary_sum
collision_detection::CollisionRobotIndustrialConstPtr collision_robot
collision_detection::CollisionWorldIndustrialConstPtr collision_world
initialization_state::InitializationState condition
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Affine3d 
goal
std::string group_name
int iter
std::vector< Eigen::VectorXd > iteration_path
Eigen::VectorXd joint_seed
Eigen::VectorXd joints
Eigen::VectorXd joints_delta
planning_scene::PlanningSceneConstPtr planning_scene
Eigen::Affine3d pose_estimate
double primary_sum
moveit::core::RobotStatePtr robot_state

Detailed Description

Internal state of Constrained_IK solver.

Definition at line 41 of file solver_state.h.


Constructor & Destructor Documentation

constrained_ik::SolverState::SolverState ( const Eigen::Affine3d &  goal,
const Eigen::VectorXd &  joint_seed 
)

SolverState Constructor.

Parameters:
goaldesired goal position to solve IK about
joint_seedjoint position (initial guess) to seed the IK solver with

Definition at line 35 of file solver_state.cpp.


Member Function Documentation

void constrained_ik::SolverState::reset ( const Eigen::Affine3d &  goal,
const Eigen::VectorXd &  joint_seed 
)

Reset the current state to default state.

Parameters:
goaldesired goal position to solve IK about
joint_seedjoint position (initial guess) to seed the IK solver with

Definition at line 40 of file solver_state.cpp.


Member Data Documentation

This is set if auxiliary reached motion or iteration limit.

Definition at line 54 of file solver_state.h.

The absolute sum of the cumulative auxiliary motion

Definition at line 53 of file solver_state.h.

Pointer to the collision robot, some constraints require it

Definition at line 57 of file solver_state.h.

Pointer to the collision world, some constraints require it

Definition at line 58 of file solver_state.h.

initialization_state::InitializationState constrained_ik::SolverState::condition

State of the IK Solver

Definition at line 55 of file solver_state.h.

Desired goal position to solve IK about

Definition at line 44 of file solver_state.h.

Move group name

Definition at line 60 of file solver_state.h.

Current number of solver iterations

Definition at line 47 of file solver_state.h.

std::vector<Eigen::VectorXd> constrained_ik::SolverState::iteration_path

Store the joint position for each iteration of the solver

Definition at line 51 of file solver_state.h.

Joint position (initial guess) to seed the IK solver with

Definition at line 45 of file solver_state.h.

Updated joint positions

Definition at line 48 of file solver_state.h.

The joint delta between this state and the previous state

Definition at line 49 of file solver_state.h.

planning_scene::PlanningSceneConstPtr constrained_ik::SolverState::planning_scene

Pointer to the planning scene, some constraints require it

Definition at line 56 of file solver_state.h.

The pose for the updated joint position from the solver

Definition at line 50 of file solver_state.h.

The absolute sum of the cumulative primary motion

Definition at line 52 of file solver_state.h.

moveit::core::RobotStatePtr constrained_ik::SolverState::robot_state

Pointer to the current robot state

Definition at line 59 of file solver_state.h.


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


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Sat Jun 8 2019 19:23:46