Public Types | Public Member Functions | Public Attributes | List of all members
robot_interaction::KinematicOptions Struct Reference

#include <kinematic_options.h>

Public Types

enum  OptionBitmask {
  TIMEOUT = 0x00000001, MAX_ATTEMPTS = 0x00000002, STATE_VALIDITY_CALLBACK = 0x00000004, LOCK_REDUNDANT_JOINTS = 0x00000008,
  RETURN_APPROXIMATE_SOLUTION = 0x00000010, DISCRETIZATION_METHOD = 0x00000020, ALL_QUERY_OPTIONS = LOCK_REDUNDANT_JOINTS | RETURN_APPROXIMATE_SOLUTION | DISCRETIZATION_METHOD, ALL = 0x7fffffff
}
 

Public Member Functions

 KinematicOptions ()
 Constructor - set all options to reasonable default values. More...
 
void setOptions (const KinematicOptions &source, OptionBitmask fields=ALL)
 
bool setStateFromIK (robot_state::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const
 

Public Attributes

unsigned int max_attempts_
 how many attempts before we give up. More...
 
kinematics::KinematicsQueryOptions options_
 other options More...
 
robot_state::GroupStateValidityCallbackFn state_validity_callback_
 This is called to determine if the state is valid. More...
 
double timeout_seconds_
 max time an IK attempt can take before we give up. More...
 

Detailed Description

Definition at line 49 of file kinematic_options.h.

Member Enumeration Documentation

Bits corresponding to each member. NOTE: when adding fields to this structure also add the field to this enum and to the setOptions() method.

Enumerator
TIMEOUT 
MAX_ATTEMPTS 
STATE_VALIDITY_CALLBACK 
LOCK_REDUNDANT_JOINTS 
RETURN_APPROXIMATE_SOLUTION 
DISCRETIZATION_METHOD 
ALL_QUERY_OPTIONS 
ALL 

Definition at line 57 of file kinematic_options.h.

Constructor & Destructor Documentation

robot_interaction::KinematicOptions::KinematicOptions ( )

Constructor - set all options to reasonable default values.

Definition at line 41 of file kinematic_options.cpp.

Member Function Documentation

void robot_interaction::KinematicOptions::setOptions ( const KinematicOptions source,
OptionBitmask  fields = ALL 
)

Copy a subset of source to this. For each bit set in fields the corresponding member is copied from source to this.

Definition at line 63 of file kinematic_options.cpp.

bool robot_interaction::KinematicOptions::setStateFromIK ( robot_state::RobotState &  state,
const std::string &  group,
const std::string &  tip,
const geometry_msgs::Pose pose 
) const

Set state using inverse kinematics

Parameters
statethe state to set
groupname of group whose joints can move
tiplink that will be posed
posedesired pose of tip link
resulttrue if IK succeeded.

Definition at line 49 of file kinematic_options.cpp.

Member Data Documentation

unsigned int robot_interaction::KinematicOptions::max_attempts_

how many attempts before we give up.

Definition at line 87 of file kinematic_options.h.

kinematics::KinematicsQueryOptions robot_interaction::KinematicOptions::options_

other options

Definition at line 93 of file kinematic_options.h.

robot_state::GroupStateValidityCallbackFn robot_interaction::KinematicOptions::state_validity_callback_

This is called to determine if the state is valid.

Definition at line 90 of file kinematic_options.h.

double robot_interaction::KinematicOptions::timeout_seconds_

max time an IK attempt can take before we give up.

Definition at line 84 of file kinematic_options.h.


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


robot_interaction
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:32