Closed mohamedsayed18 closed 2 years ago
I recommend taking a look at the one below which is for the one in tesseract_ros_workcell with a robot and external positioner. The positioner sample resolution min and max are optional and if not provided it uses the joint limits.
specifically what is the difference between these two classes class: KDLInvKinChainLMAFactory and KDLInvKinChainNRFactory?
They are different algorithms for solving inverse kinematics provided by KDL. I recommend using OPW if possible as shown below.
kinematic_plugins:
inv_kin_plugins:
manipulator:
REPInvKin:
class: REPInvKinFactory
default: true
config:
manipulator_reach: 2.3
positioner_sample_resolution:
- name: positioner_base_joint
value: 0.1
min: -0.2
max: 0.2
- name: positioner_joint_1
value: 0.1
min: -0.2
max: 0.2
positioner:
class: KDLFwdKinChainFactory
config:
base_link: positioner_base_link
tip_link: positioner_tool0
manipulator:
class: OPWInvKinFactory
config:
base_link: robot_base_link
tip_link: robot_tool0
params:
a1: 0.175
a2: -0.175
b: 0.00
c1: 0.495
c2: 0.9
c3: 0.96
c4: 0.135
offsets: [0, 0, -1.57079632679, 0, 0, 0]
sign_corrections: [1, 1, 1, 1, 1, 1]
I think this file is not pushed yet to the tesseract_work_cell yet
@mohamedsayed18 Thanks for the reminder, I just merged it into master.
In this assert
https://github.com/ros-industrial/tesseract/blob/74492dc802c36e7310f937061622bc828b3f229b/tesseract_kinematics/core/src/kinematic_group.cpp#L108-L109
tip_link_poses
is defined by the working frame when creating our ManipulatorInfo
object
where do the values in the working_frames_
come from?
It is defined in the constructor. In the case of the robot with an external positioner, it would the tip_link o the positioner and any child links. In the case of the robot only it would be the base_link and any other static link in the environment.
Do I need to use a specific planner "FREESPACE_PLANNER_NAME" for example that supports the external axis inverse kinematics?
They should be independent. They all use the JoingGroup or KinematicsGroup interface. Are you running into any issues using "FREESPACE_PLANNER_NAME"?
I'm trying to execute two stateWaypoints(start and another point). Somehow I'm still failing in this assert https://github.com/tesseract-robotics/tesseract/blob/74492dc802c36e7310f937061622bc828b3f229b/tesseract_kinematics/core/src/kinematic_group.cpp#L108-L109
My working frames vector contains the positioner_tool0 as expected
but the tip_link_pose.working_frame
is set to world
regardless of the value in the ManipulatorInfo
I think the error is in this line
https://github.com/tesseract-robotics/tesseract/blob/8445d507a2bbe3ec5b5e819a835a0d33758cc13b/tesseract_kinematics/core/include/tesseract_kinematics/core/validate.h#L64
Should it be the working_frame instead of the getBaseLinkName
?
You are correct there is an issue with this function if your kinematic arrangement is rep. I have PR coming to fix the function.
I have opened PR #658 which should resolve the issue.
What are the correct values for the
kinematics_plugin_config
? specifically what is the difference between these two classesclass: KDLInvKinChainLMAFactory
andKDLInvKinChainNRFactory
? In the base_link and tip_link, I add the same value for both classes which are specified in my chain but my code fails at this assert https://github.com/ros-industrial/tesseract/blob/74492dc802c36e7310f937061622bc828b3f229b/tesseract_kinematics/core/src/kinematic_group.cpp#L108-L109I'm having my chain defined as follows