Class KinematicOptionsMap

Class Documentation

class KinematicOptionsMap

Public Functions

KinematicOptionsMap()

Constructor - set all options to reasonable default values.

bool setStateFromIK(moveit::core::RobotState &state, const std::string &key, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const

Set state using inverse kinematics.

Parameters:
  • state – the state to set

  • key – used to lookup the options to use

  • group – name of group whose joints can move

  • tip – link that will be posed

  • pose – desired pose of tip link

  • result – true if IK succeeded.

KinematicOptions getOptions(const std::string &key) const

Get the options to use for a particular key. To get the default values pass key = KinematicOptionsMap::DEFAULT

void setOptions(const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields = KinematicOptions::ALL)

Set some of the options to be used for a particular key.

@fields which options to set for the key.

Parameters:
void merge(const KinematicOptionsMap &other)

Merge all options from other into this. Values in other (including defaults_) take precedence over values in this.

Public Static Attributes

static const std::string DEFAULT

When used as key this means the default value.

static const std::string ALL

When used as key this means set ALL keys (including default)