I am working on a project where I need to control Baxter in a virtual environment, then port that script over to control the real robot. I am looking for guidance on how to do this, I assume it would involve the ROS interface tool.
I also need to modify the model to use my own custom end effector. Will CoppeliaSim calculate inverse kinematics for me in order to move the arms correctly?
Make real Baxter mimic simulation
Re: Make real Baxter mimic simulation
Hello,
if your next step is to control the real robot with the same controller, then it would be wise to write your controller as a CoppeliaSim-independent code, e.g. Python connecting to CoppeliaSim or the real baxter via ROS indeed.
The Baxter model that comes with CoppeliaSim doesn't have any end-effectors attach, you can attach whatever you want to there.
As for IK: of course you could use CoppeliaSim's IK, but then if you later need to run the same external controller to handle the real Baxter, this probably wouldn't make sense.
Cheers
if your next step is to control the real robot with the same controller, then it would be wise to write your controller as a CoppeliaSim-independent code, e.g. Python connecting to CoppeliaSim or the real baxter via ROS indeed.
The Baxter model that comes with CoppeliaSim doesn't have any end-effectors attach, you can attach whatever you want to there.
As for IK: of course you could use CoppeliaSim's IK, but then if you later need to run the same external controller to handle the real Baxter, this probably wouldn't make sense.
Cheers
Re: Make real Baxter mimic simulation
Hello,
I will have a computer available to run CoppeliaSim during operation, so technically it doesn't matter if the code is independent or not. My plan is to use CoppeliaSim's IK solver to handle my custom gripper, then write those joint values to the robot via a ROS interface.
I am trying to get IK running now, and running into some trouble. I can get it to work for very close waypoints based on the IK solver example scene, but for points that are far away the solver returns an empty set.
I will have a computer available to run CoppeliaSim during operation, so technically it doesn't matter if the code is independent or not. My plan is to use CoppeliaSim's IK solver to handle my custom gripper, then write those joint values to the robot via a ROS interface.
I am trying to get IK running now, and running into some trouble. I can get it to work for very close waypoints based on the IK solver example scene, but for points that are far away the solver returns an empty set.
Re: Make real Baxter mimic simulation
Can you give us more details about what fails exactly? Is it e.g. simIK.findConfig? Can you share a link to a minimalistic, self-contained scene that illustrates your problem?
Cheers
Cheers
Re: Make real Baxter mimic simulation
Not sure how to link to a scene, but I can describe what I did as it's pretty simplistic. Using the ikPathGeneration.ttt example scene as a baseline, I added Baxter into a scene and used the following script for the upperBody object. I attached a model of my custom gripper and added waypoints onto the gripper and into the environment as movement goals. The problem is that when the waypoint is far away, the generated path is a null set, which I assume means there was no solution found. I have tried adding more points to the path to no avail.
Code: Select all
sim=require'sim'
simIK=require'simIK'
function hopThroughConfigs(path,joints,reverse,dynModel)
local lb=sim.setStepping(true)
local s=1
local g=#path/#joints
local incr=1
if reverse then
s=#path/#joints
g=1
incr=-1
end
for i=s,g,incr do
if dynModel then
for j=1,#joints,1 do
sim.setJointTargetPosition(joints[j],path[(i-1)*#joints+j])
--sim.setJointTargetPosition(joints[6],1)
end
else
for j=1,#joints,1 do
sim.setJointPosition(joints[j],path[(i-1)*#joints+j])
--sim.setJointPosition(joints[6],1)
end
end
sim.step()
end
sim.setStepping(lb)
end
function sysCall_thread()
local simBase=sim.getObject('.')
local simTip=sim.getObject('./tip')
local simGoal=sim.getObject('/waypoint1')
--local simGoal=sim.getObject('/closePoint')
local simJoints={}
simJoints[1]=sim.getObject('./joint1[0]')
simJoints[2]=sim.getObject('./joint1[0]/rightArm_joint')
simJoints[3]=sim.getObject('./joint1[0]/rightArm_joint/rightArm_joint')
simJoints[4]=sim.getObject('./joint1[0]/rightArm_joint/rightArm_joint/rightArm_joint')
simJoints[5]=sim.getObject('./joint1[0]/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint')
simJoints[6]=sim.getObject('./joint1[0]/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint')
simJoints[7]=sim.getObject('./joint1[0]/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint/rightArm_joint')
sim.step() -- make sure we have skipped the first simulation step,
-- otherwise following cmd won't reflect reality
local dynModel=sim.isDynamicallyEnabled(simJoints[1])
-- Prepare an ik group, using the convenience function 'simIK.addElementFromScene':
local ikEnv=simIK.createEnvironment()
local ikGroup=simIK.createGroup(ikEnv)
local ikElement,simToIkMap=simIK.addElementFromScene(ikEnv,ikGroup,simBase,simTip,simGoal,simIK.constraint_pose)
-- Retrieve some handles of objects created in the IK environment:
local ikTip=simToIkMap[simTip]
local ikJoints={}
for i=1,#simJoints,1 do
ikJoints[i]=simToIkMap[simJoints[i]]
end
-- Generate a path:
local path=simIK.generatePath(ikEnv,ikGroup,ikJoints,ikTip,500)
if #path==0 then
print('No IK Solution Found!!!')
end
simIK.eraseEnvironment(ikEnv)
-- Hop through the path configurations:
while true do
hopThroughConfigs(path,simJoints,false,dynModel)
hopThroughConfigs(path,simJoints,true,dynModel)
end
end
Re: Make real Baxter mimic simulation
I am still failing at completely understanding without the exact same scene and code. From what I can tell, make sure to notice following:
Ik in CoppeliaSim works by linearizing around current configuration (i.e. using the Jacobian). If the target lies far away, linearization might overshoot, or drive the mechanism into the wrong direction or with wrong values. IK is not path planning. If you need to find a configuration that corresponds to an end-effector that lies gfar away, use simIK.findConfig.
To alleviate problems linked to above remarks, you can make smaller steps to drive the arm, or use a damped version of the IK solver.
Additionally, never forget that IK simply ignores joint limits and won't magically work around them: there is always a straight line from one IK config to the next (in 3D space)
Cheers
Ik in CoppeliaSim works by linearizing around current configuration (i.e. using the Jacobian). If the target lies far away, linearization might overshoot, or drive the mechanism into the wrong direction or with wrong values. IK is not path planning. If you need to find a configuration that corresponds to an end-effector that lies gfar away, use simIK.findConfig.
To alleviate problems linked to above remarks, you can make smaller steps to drive the arm, or use a damped version of the IK solver.
Additionally, never forget that IK simply ignores joint limits and won't magically work around them: there is always a straight line from one IK config to the next (in 3D space)
Cheers