Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
grl::vrep::InverseKinematicsVrepPlugin Class Reference

#include <InverseKinematicsVrepPlugin.hpp>

+ Collaboration diagram for grl::vrep::InverseKinematicsVrepPlugin:

Public Types

enum  AlgToUseE { AlgToUseE::ik, AlgToUseE::multiIterQP, AlgToUseE::singleIterQP }
 Configures updateKinematics the algorithm the kinematics should use for solving. More...
 
enum  GoalPosE { GoalPosE::realGoalPosition, GoalPosE::debugGoalPosition }
 Configures updateKinematics with the goal the kinematics should aim for. More...
 
typedef std::tuple< std::string,std::string > Params
 
enum  PostureTaskStrategyE { PostureTaskStrategyE::constant, PostureTaskStrategyE::updateToCurrent }
 
enum  VrepVFControllerParamsIndex { DesiredKinematicsObjectName, IKGroupName }
 

Public Member Functions

void construct (Params params=defaultParams())
 
void debugFrames (bool print=false)
 
 InverseKinematicsVrepPlugin ()
 
void run_one ()
 
void solve ()
 
void testPose ()
 
void updateKinematics (const bool runOnce=false, const GoalPosE solveForPosition=GoalPosE::realGoalPosition, const AlgToUseE alg=AlgToUseE::multiIterQP, const PostureTaskStrategyE postureStrategy=PostureTaskStrategyE::constant)
 

Static Public Member Functions

static Params defaultParams ()
 

Public Attributes

std::vector< int > bodyHandles_
 
vrep::VrepRobotArmDriver::State currentArmState_
 
int ikGroupBaseHandle_
 
std::string ikGroupBaseName_
 
int ikGroupHandle_
 
int ikGroupTargetHandle_
 
std::string ikGroupTargetName_
 
int ikGroupTipHandle_
 
std::string ikGroupTipName_
 
std::vector< int > jointHandles_
 
std::vector< std::string > jointNames_
 
std::vector< int > linkHandles_
 
std::vector< std::string > linkNames_
 
std::vector< int > linkRespondableHandles_
 
std::vector< std::string > linkRespondableNames_
 
bool ranOnce_ = false
 
std::vector< rbd::Body > rbd_bodies_
 
std::vector< std::string > rbd_bodyNames_
 
std::vector< sva::RBInertia< double > > rbd_inertias_
 
std::vector< int > rbd_jointHandles_
 
std::vector< std::string > rbd_jointNames_
 
std::vector< rbd::Joint > rbd_joints_
 
std::vector< rbd::MultiBodyConfig > rbd_mbcs_
 
rbd::MultiBodyGraph rbd_mbg_
 
std::vector< rbd::MultiBody > rbd_mbs_
 
std::vector< rbd::MultiBodyConfig > rbd_preferred_mbcs_
 preferred posture to resolve ambiguities More...
 
std::vector< rbd::MultiBodyConfig > rbd_prev_mbcs_
 rbd_prev_mbcs_ is for debugging More...
 
std::string robotFlangeTipName_
 
std::shared_ptr< vrep::VrepRobotArmDriverVrepRobotArmDriverMeasuredP_
 
std::shared_ptr< vrep::VrepRobotArmDriverVrepRobotArmDriverSimulatedP_
 

Detailed Description

This object handles taking data from a V-REP based arm simulation using it to configure an arm constrained optimization algorithm, runs the algorithm, then updates the simulation accordingly.

The types of problems this can solve include reaching a goal position, applying the desired levels of force to a system, and avoiding obstacles at each time step.

See also
the Tasks libraryhttps://github.com/jrl-umi3218/Tasks for a full set of possible capabilities.
Todo:
verify Robotiiwa is the correct base, and RobotMillTipTarget is the right target, because if the transform doesn't match the one in the jacobian the algorithm will break

Definition at line 154 of file InverseKinematicsVrepPlugin.hpp.

Member Typedef Documentation

§ Params

typedef std::tuple< std::string ,std::string > grl::vrep::InverseKinematicsVrepPlugin::Params

Definition at line 171 of file InverseKinematicsVrepPlugin.hpp.

Member Enumeration Documentation

§ AlgToUseE

Configures updateKinematics the algorithm the kinematics should use for solving.

Enumerator
ik 
multiIterQP 
singleIterQP 

Definition at line 472 of file InverseKinematicsVrepPlugin.hpp.

§ GoalPosE

Configures updateKinematics with the goal the kinematics should aim for.

Enumerator
realGoalPosition 
debugGoalPosition 

Definition at line 470 of file InverseKinematicsVrepPlugin.hpp.

§ PostureTaskStrategyE

Configures if the target pose objective should stick to the constant initalized version, or if it should update every iteration in tasks::qp::PostureTask https://github.com/jrl-umi3218/Tasks/blob/15aff94e3e03f6a161a87799ca2cf262b756bd0c/src/QPTasks.h#L426

Enumerator
constant 
updateToCurrent 

Definition at line 476 of file InverseKinematicsVrepPlugin.hpp.

§ VrepVFControllerParamsIndex

Enumerator
DesiredKinematicsObjectName 
IKGroupName 

Definition at line 163 of file InverseKinematicsVrepPlugin.hpp.

Constructor & Destructor Documentation

§ InverseKinematicsVrepPlugin()

grl::vrep::InverseKinematicsVrepPlugin::InverseKinematicsVrepPlugin ( )
inline
Todo:
need to call parent constructor:

Constructor

Definition at line 181 of file InverseKinematicsVrepPlugin.hpp.

Member Function Documentation

§ construct()

void grl::vrep::InverseKinematicsVrepPlugin::construct ( Params  params = defaultParams())
inline
Todo:
TODO(ahundt) accept params for both simulated and measured arms

for why this is named as it is see: https://github.com/jrl-umi3218/Tasks/blob/master/tests/arms.h#L34

Todo:
TODO(ahundt) replace hardcoded joint strings with a vrep tree traversal object that generates an RBDyn MultiBodyGraph
Todo:
TODO(ahundt) fix hard coded Revolute vs fixed joint https://github.com/ahundt/grl/issues/114
Todo:
TODO(ahundt) last "joint" RobotMillTip is really fixed...
Todo:
TODO(ahundt) extract real inertia and center of mass from V-REP with http://www.coppeliarobotics.com/helpFiles/en/regularApi/simGetShapeMassAndInertia.htm
Todo:
TODO(ahundt) consider the origin of the inertia! https://github.com/jrl-umi3218/Tasks/issues/10#issuecomment-257198604
Todo:
TODO(ahundt) add real support for links, particularly the respondable aspects, see LBR_iiwa_14_R820_joint1_resp in RoboneSimulation.ttt
Todo:
verify object lifetimes
Todo:
read objective rows from vrep
Todo:
set vrep explicit handling of IK here, plus unset in destructor of this object

Definition at line 186 of file InverseKinematicsVrepPlugin.hpp.

§ debugFrames()

void grl::vrep::InverseKinematicsVrepPlugin::debugFrames ( bool  print = false)
inline

Set dummy frames named Dummy0 to Dummy19 to the current state of the RBDyn and V-REP representations of joints for debugging.

Definition at line 377 of file InverseKinematicsVrepPlugin.hpp.

§ defaultParams()

static Params grl::vrep::InverseKinematicsVrepPlugin::defaultParams ( )
inlinestatic

Definition at line 173 of file InverseKinematicsVrepPlugin.hpp.

§ run_one()

void grl::vrep::InverseKinematicsVrepPlugin::run_one ( )
inline

may not need this it is in the base class blocking call, call in separate thread, just allocates memory

Definition at line 691 of file InverseKinematicsVrepPlugin.hpp.

§ solve()

void grl::vrep::InverseKinematicsVrepPlugin::solve ( )
inline

may not need this it is in the base class this will have output blocking call, call in separate thread, just allocates memory this runs the actual optimization algorithm

Definition at line 702 of file InverseKinematicsVrepPlugin.hpp.

§ testPose()

void grl::vrep::InverseKinematicsVrepPlugin::testPose ( )
inline

simulation tick time step in float seconds from vrep API call

Todo:
TODO(ahundt) rethink where/when/how to send command for the joint angles. Return to LUA? Set Directly? Distribute via vrep send message command?

Definition at line 438 of file InverseKinematicsVrepPlugin.hpp.

§ updateKinematics()

void grl::vrep::InverseKinematicsVrepPlugin::updateKinematics ( const bool  runOnce = false,
const GoalPosE  solveForPosition = GoalPosE::realGoalPosition,
const AlgToUseE  alg = AlgToUseE::multiIterQP,
const PostureTaskStrategyE  postureStrategy = PostureTaskStrategyE::constant 
)
inline

Runs inverse kinematics or constrained optimization at every simulation time step

Parameters
runOnceSet runOnce = true to only update kinematics once for debugging purposes. runOnce = false runs this function at every time step.
Todo:
TODO(ahundt) change source of current state based on if physical arm is running
Todo:
TODO(ahundt) move code below here back into separate independent setup and solve functions, move some steps like limits to construct()

simulation tick time step in float seconds from vrep API call

Todo:
TODO(ahundt) rethink where/when/how to send command for the joint angles. Return to LUA? Set Directly? Distribute via vrep send message command?
Todo:
TODO(ahundt) make solver object a member variable if possible, initialize in constructor

limits must be organized as described in https://github.com/jrl-umi3218/Tasks/issues/10#issuecomment-257793242

Todo:
TODO(ahundt) ulimits aren't the same size as jointHandles_, need velocity limits too
Todo:
TODO(ahundt) hardcoded mill tip joint limits, remove these
Todo:
TODO(ahundt) replace hardcoded velocity limits with real and useful limits specific to each joint loaded from V-REP or another file.
Todo:
TODO(ahundt) was this commented correctly?
Todo:
TODO(ahundt) remove BOOST_VERIFY(), try/catch solver failure, print an error, send a v-rep message, and shut down solver or enter a hand guiding mode

Definition at line 481 of file InverseKinematicsVrepPlugin.hpp.

Member Data Documentation

§ bodyHandles_

std::vector<int> grl::vrep::InverseKinematicsVrepPlugin::bodyHandles_

Definition at line 717 of file InverseKinematicsVrepPlugin.hpp.

§ currentArmState_

vrep::VrepRobotArmDriver::State grl::vrep::InverseKinematicsVrepPlugin::currentArmState_

Definition at line 753 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupBaseHandle_

int grl::vrep::InverseKinematicsVrepPlugin::ikGroupBaseHandle_

Definition at line 742 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupBaseName_

std::string grl::vrep::InverseKinematicsVrepPlugin::ikGroupBaseName_

Definition at line 746 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupHandle_

int grl::vrep::InverseKinematicsVrepPlugin::ikGroupHandle_

Definition at line 741 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupTargetHandle_

int grl::vrep::InverseKinematicsVrepPlugin::ikGroupTargetHandle_

Definition at line 744 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupTargetName_

std::string grl::vrep::InverseKinematicsVrepPlugin::ikGroupTargetName_

Definition at line 748 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupTipHandle_

int grl::vrep::InverseKinematicsVrepPlugin::ikGroupTipHandle_

Definition at line 743 of file InverseKinematicsVrepPlugin.hpp.

§ ikGroupTipName_

std::string grl::vrep::InverseKinematicsVrepPlugin::ikGroupTipName_

Definition at line 747 of file InverseKinematicsVrepPlugin.hpp.

§ jointHandles_

std::vector<int> grl::vrep::InverseKinematicsVrepPlugin::jointHandles_
Todo:
move this item back into VrepRobotArmDriver

Definition at line 734 of file InverseKinematicsVrepPlugin.hpp.

§ jointNames_

std::vector<std::string> grl::vrep::InverseKinematicsVrepPlugin::jointNames_

Definition at line 737 of file InverseKinematicsVrepPlugin.hpp.

§ linkHandles_

std::vector<int> grl::vrep::InverseKinematicsVrepPlugin::linkHandles_

Definition at line 735 of file InverseKinematicsVrepPlugin.hpp.

§ linkNames_

std::vector<std::string> grl::vrep::InverseKinematicsVrepPlugin::linkNames_

Definition at line 738 of file InverseKinematicsVrepPlugin.hpp.

§ linkRespondableHandles_

std::vector<int> grl::vrep::InverseKinematicsVrepPlugin::linkRespondableHandles_

Definition at line 736 of file InverseKinematicsVrepPlugin.hpp.

§ linkRespondableNames_

std::vector<std::string> grl::vrep::InverseKinematicsVrepPlugin::linkRespondableNames_

Definition at line 739 of file InverseKinematicsVrepPlugin.hpp.

§ ranOnce_

bool grl::vrep::InverseKinematicsVrepPlugin::ranOnce_ = false

Definition at line 755 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_bodies_

std::vector<rbd::Body> grl::vrep::InverseKinematicsVrepPlugin::rbd_bodies_

Definition at line 713 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_bodyNames_

std::vector<std::string> grl::vrep::InverseKinematicsVrepPlugin::rbd_bodyNames_

Definition at line 716 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_inertias_

std::vector<sva::RBInertia<double> > grl::vrep::InverseKinematicsVrepPlugin::rbd_inertias_

Definition at line 714 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_jointHandles_

std::vector<int> grl::vrep::InverseKinematicsVrepPlugin::rbd_jointHandles_

rbd "joints" include fixed joints that bridge various v-rep objects like the world origin and the ik group base. This is organized a bit differently from the v-rep joint names because we need additional fixed "joints" so we have transforms that match the V-REP scene

Definition at line 729 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_jointNames_

std::vector<std::string> grl::vrep::InverseKinematicsVrepPlugin::rbd_jointNames_

rbd "joints" include fixed joints that bridge various v-rep objects like the world origin and the ik group base. This is organized a bit differently from the v-rep joint names because we need additional fixed "joints" so we have transforms that match the V-REP scene

Definition at line 723 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_joints_

std::vector<rbd::Joint> grl::vrep::InverseKinematicsVrepPlugin::rbd_joints_

Definition at line 715 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_mbcs_

std::vector<rbd::MultiBodyConfig> grl::vrep::InverseKinematicsVrepPlugin::rbd_mbcs_

Definition at line 708 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_mbg_

rbd::MultiBodyGraph grl::vrep::InverseKinematicsVrepPlugin::rbd_mbg_

Definition at line 706 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_mbs_

std::vector<rbd::MultiBody> grl::vrep::InverseKinematicsVrepPlugin::rbd_mbs_

Definition at line 707 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_preferred_mbcs_

std::vector<rbd::MultiBodyConfig> grl::vrep::InverseKinematicsVrepPlugin::rbd_preferred_mbcs_

preferred posture to resolve ambiguities

Definition at line 712 of file InverseKinematicsVrepPlugin.hpp.

§ rbd_prev_mbcs_

std::vector<rbd::MultiBodyConfig> grl::vrep::InverseKinematicsVrepPlugin::rbd_prev_mbcs_

rbd_prev_mbcs_ is for debugging

Definition at line 710 of file InverseKinematicsVrepPlugin.hpp.

§ robotFlangeTipName_

std::string grl::vrep::InverseKinematicsVrepPlugin::robotFlangeTipName_

Definition at line 749 of file InverseKinematicsVrepPlugin.hpp.

§ VrepRobotArmDriverMeasuredP_

std::shared_ptr<vrep::VrepRobotArmDriver> grl::vrep::InverseKinematicsVrepPlugin::VrepRobotArmDriverMeasuredP_

Definition at line 752 of file InverseKinematicsVrepPlugin.hpp.

§ VrepRobotArmDriverSimulatedP_

std::shared_ptr<vrep::VrepRobotArmDriver> grl::vrep::InverseKinematicsVrepPlugin::VrepRobotArmDriverSimulatedP_

Definition at line 751 of file InverseKinematicsVrepPlugin.hpp.


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