From: Max B. <m.j...@gm...> - 2019-03-24 10:28:56
|
Hi all, Just to elaborate a bit on my previous mail. One thing that I'm struggling with is the choice to create a CompoundStateSpace with 6 SO2 StateSpace Subspaces. This would give 6 states with an angle, which can represent the six joint angles. With FK from KDL and the URDF I can make sure to meet the goals and constraints for the end effector in cartesian space. Or I could create a SE3 State for the end effector, which has 6DOF and use IK to find the joint values. For the first case I am struggling with creating the correct distance and interpolate functions since the sanity checks are not passing: Interpolation to midpoint state does not lead to distances that satisfy the triangle inequality (1.037541 difference) For the second case I am failing to understand how to implement it such that I get smooth joint paths out of it, especially for a robot which would have more than 6 joints and hence computing IK for subsequent samples could result in non smooth paths. What would be the best way forward? Gr Max *Case 1:* class KinematicChainSpace : public ob::CompoundStateSpace { public: KinematicChainSpace(unsigned int numLinks, urdf::Model urdfModel, KDL::Chain kdlChain, Environment *env = NULL) : ob::CompoundStateSpace(), numLinks_(numLinks), urdfModel_(urdfModel), kdlChain_(kdlChain), environment_(env) { for (unsigned int i = 0; i < numLinks; ++i) { addSubspace(ob::StateSpacePtr(new ob::SO2StateSpace()), 1.); ROS_INFO("Added %i/%i subspace to the KinematicChainSpace.", i, numLinks); } lock(); } *Case 2:* class KinematicChainSpace : public ob::SE3StateSpace { public: KinematicChainSpace(unsigned int numLinks, urdf::Model urdfModel, KDL::Chain kdlChain) : ob::SE3StateSpace(), numLinks_(numLinks), urdfModel_(urdfModel), kdlChain_ (kdlChain) { ROS_INFO("Created SE3StateSpace for a %i link robot. ", numLinks); lock(); } Op wo 20 mrt. 2019 om 07:08 schreef <m.j...@gm...>: > Hi all, > > > > Currently I am trying to use OMPL to create a motion planner for a > manipulator with 6 revolute joints. I’ve studied the example of the n-link > in plane robot that is shown in the kinematic chain examples but I’m having > trouble to create a 6 link revolute robot. Does anyone know of an example > for a similar robot? Collision avoidance does not have to be included. > > > > Kind regards, > > > > Max > |