Internal state of Constrained_IK solver. More...
#include <solver_state.h>
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 |
Internal state of Constrained_IK solver.
Definition at line 41 of file solver_state.h.
| constrained_ik::SolverState::SolverState | ( | const Eigen::Affine3d & | goal, |
| const Eigen::VectorXd & | joint_seed | ||
| ) |
SolverState Constructor.
| goal | desired goal position to solve IK about |
| joint_seed | joint position (initial guess) to seed the IK solver with |
Definition at line 35 of file solver_state.cpp.
| void constrained_ik::SolverState::reset | ( | const Eigen::Affine3d & | goal, |
| const Eigen::VectorXd & | joint_seed | ||
| ) |
Reset the current state to default state.
| goal | desired goal position to solve IK about |
| joint_seed | joint position (initial guess) to seed the IK solver with |
Definition at line 40 of file solver_state.cpp.
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.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Affine3d constrained_ik::SolverState::goal |
Desired goal position to solve IK about
Definition at line 44 of file solver_state.h.
| std::string constrained_ik::SolverState::group_name |
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.
| Eigen::VectorXd constrained_ik::SolverState::joint_seed |
Joint position (initial guess) to seed the IK solver with
Definition at line 45 of file solver_state.h.
| Eigen::VectorXd constrained_ik::SolverState::joints |
Updated joint positions
Definition at line 48 of file solver_state.h.
| Eigen::VectorXd constrained_ik::SolverState::joints_delta |
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.
| Eigen::Affine3d constrained_ik::SolverState::pose_estimate |
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.