Functions
fanuc::utils Namespace Reference

Functions

void linkage_transform (const std::vector< double > &joints_in, std::vector< double > *joints_out, double J23_factor=0)
 Corrects for parallel linkage coupling between joints.
void linkage_transform (const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out, double J23_factor=0)
 Corrects for parallel linkage coupling between joints.

Function Documentation

void fanuc::utils::linkage_transform ( const std::vector< double > &  joints_in,
std::vector< double > *  joints_out,
double  J23_factor = 0 
)

Corrects for parallel linkage coupling between joints.

Parameters:
[in]joints_ininput joint angles
[out]joints_outoutput joint angles
[in]J23_factorLinkage factor for J2-J3. J3_out = J3_in + j23_factor * J2_in

Definition at line 60 of file fanuc_utils.cpp.

void fanuc::utils::linkage_transform ( const trajectory_msgs::JointTrajectoryPoint &  pt_in,
trajectory_msgs::JointTrajectoryPoint *  pt_out,
double  J23_factor = 0 
)

Corrects for parallel linkage coupling between joints.

Parameters:
[in]pt_ininput joint trajectory point
[out]pt_outoutput joint trajectory point
[in]J23_factorLinkage factor for J2-J3. J3_out = J3_in + j23_factor * J2_in

Definition at line 52 of file fanuc_utils.cpp.



fanuc_driver
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Sat Jun 8 2019 20:43:30