20"Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame.\n\n"
21"Parameters:\n"
22"\tmodel: model of the kinematic tree\n"
23"\tdata: data related to the model\n"
24"\tjoint_id: index of the joint\n"
25"\treference_frame: reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)\n"
26"\tplacement: relative placement to the joint frame\n");
31"Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input.\n\n"
32"Parameters:\n"
33"\tmodel: model of the kinematic tree\n"
34"\tdata: data related to the model\n"
35"\tjoint_id: index of the joint\n"
36"\treference_frame: reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)\n");
41"Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input.\n\n"
42"Parameters:\n"
43"\tmodel: model of the kinematic tree\n"
44"\tdata: data related to the model\n"
45"\tframe_id: index of the frame\n"
46"\treference_frame: reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)\n");