PIK ROS
Public Member Functions | List of all members
PikRos::Pik Class Reference

Prioritized inverse kinematics solver. More...

#include <PikRos.hpp>

Public Member Functions

 Pik (ros::NodeHandle &nh_, const std::string &robot_name, const std::string &joint_model_group_name, const Settings &settings=Settings())
 Construct a new Pik object. More...
 
Eigen::VectorXd solve (const std::vector< IkTask > &ik_tasks, const Eigen::VectorXd &q_initial_guess)
 Solves a prioritized inverse kinematics problem. More...
 
void goToJointPosition (const Eigen::VectorXd &q) const
 Moves the robot to desired joint positions. More...
 
void printErrors (const Eigen::VectorXd &q, const std::vector< IkTask > &ik_tasks) const
 Prints task errors for a given joint position vector. More...
 

Detailed Description

Prioritized inverse kinematics solver.

Solves the positional inverse kinematics problem given a vector of Ik tasks with descending priorities

Constructor & Destructor Documentation

◆ Pik()

Pik::Pik ( ros::NodeHandle &  nh_,
const std::string &  robot_name,
const std::string &  joint_model_group_name,
const Settings settings = Settings() 
)

Construct a new Pik object.

Parameters
nh_ROS node handle
robot_nameNamespace for robot description
joint_model_group_nameJoint model group name in MoveIt
settingsPikRos::Settings object

Member Function Documentation

◆ goToJointPosition()

void Pik::goToJointPosition ( const Eigen::VectorXd &  q) const

Moves the robot to desired joint positions.

Parameters
qEigen::VectorXd Joint position vector

◆ printErrors()

void Pik::printErrors ( const Eigen::VectorXd &  q,
const std::vector< IkTask > &  ik_tasks 
) const

Prints task errors for a given joint position vector.

Parameters
qEigen::VectorXd Joint position vector
ik_tasksstd::vector<IkTask> Inverse kinematics tasks;

◆ solve()

Eigen::VectorXd Pik::solve ( const std::vector< IkTask > &  ik_tasks,
const Eigen::VectorXd &  q_initial_guess 
)

Solves a prioritized inverse kinematics problem.

Parameters
ik_tasksIk tasks std::vector<IkTask> from higher priority to lower
q_initial_guessInitial guess for a joint position vector q
Returns
Eigen::VectorXd solution joint positions

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