Yawing Bipedal Robot

Typically: "How do I... ", "How can I... " questions
Post Reply
elsonedo
Posts: 13
Joined: 24 Feb 2015, 16:17

Yawing Bipedal Robot

Post by elsonedo »

Hello, I'm new here in V-REP simulator.. recently I just learn the script of hexapod1 by lyall randell.. Now I have my own bipedal robot that i want to simulate it..

I want to apply the exact code in the hexapod1

Code: Select all

-- yawing
		p[3]=p[3]+0.0*sizeFactor
		o[3]=o[3]+30*math.pi/180
		simMoveToPosition(legBase,antBase,p,o,vel,accel)
		o[3]=o[3]-60*math.pi/180
		simMoveToPosition(legBase,antBase,p,o,vel,accel)
		o[3]=o[3]+30*math.pi/180
		simMoveToPosition(legBase,antBase,p,o,vel,accel)
		p[3]=p[3]-0.0*sizeFactor
		simMoveToPosition(legBase,antBase,p,o,vel,accel)


i change for my bipedal robot :

Code: Select all

-- yawing
		p[3]=p[3]+0.0*sizeFactor
		o[3]=o[3]+15*math.pi/180
		simMoveToPosition(legBase,bipedBase,p,o,vel,accel)
		o[3]=o[3]-30*math.pi/180
		simMoveToPosition(legBase,bipedBase,p,o,vel,accel)
		o[3]=o[3]+15*math.pi/180
		simMoveToPosition(legBase,bipedBase,p,o,vel,accel)
		p[3]=p[3]-0.0*sizeFactor
		simMoveToPosition(legBase,bipedBase,p,o,vel,accel)
I have made the correct hierarchy and wrote the script just for yawing the joint, all joint already in IK and hybrid etc.. but when I start the simulation the joint it not yawing. what should I do to make the joint yawing? I would like my robot to rotate yawing and back again to original position same as like the hexapod1 yawing movement.

here is my robot picture and the scene :
Image

here is what i wanted to do for yawing movement :
Image

coppelia
Site Admin
Posts: 7928
Joined: 14 Dec 2012, 00:25

Re: Yawing Bipedal Robot

Post by coppelia »

Hello,

in your case, for yawing, you need to change the orientation of the target dummy. In the hexapod model, the IK task is simply to follow the target position, not the orientation. In your case, you also want to follow the orientation. Are your IK element constraints set to X,Y,Z,aphe-beta,gamma?

Cheers

elsonedo
Posts: 13
Joined: 24 Feb 2015, 16:17

Re: Yawing Bipedal Robot

Post by elsonedo »

Thank you Coppelia! it works, I forgot to make the IK element constraints set to alpha-beta,gamma .. now I can continue to exploring the program and will make my bipedal robot run.. thanks !

Cheers

Jay
Posts: 11
Joined: 14 Oct 2015, 16:34

Re: Yawing Bipedal Robot

Post by Jay »

Hi Admin,

I was wondering can you post some explanation of "simMoveToPosition" since there is nothing but a 'DEPRECATED'. Similar to the Lua parameters details for "number result,table_3 newPos,table_4 newQuaternion,table_4 newVel,table_4 newAccel,number timeLeft=simRMLMoveToPosition(number objectHandle,number relativeToObjectHandle,number flags,table_4 currentVel,table_4 currentAccel,table_4 maxVel,table_4 maxAccel,table_4 maxJerk,table_3 targetPosition,table_4 targetQuaternion,table_4 targetVel)". Thanks.

coppelia
Site Admin
Posts: 7928
Joined: 14 Dec 2012, 00:25

Re: Yawing Bipedal Robot

Post by coppelia »

Hello,

the function is not described since it is deprecated (as it says in the documentation) and shouldn't be used anymore, otherwise you might get compatibility issues in future. Use simRMLMoveToPosition instead.

Here anyway, for your info, the deprecated documentation:

Description:
Moves an object to a given position and/or orientation. This function can only be called from child scripts running in a thread (since this is a blocking operation) and is not available from the C-API. If you want to move several objects at the same time from the same thread, you will have to attach the objects to joints and use the simMoveToJointPositions function (or you could manually move all objects little by little with the simSetObjectPosition and simSetObjectOrientation functions). See also simMoveToObject and simFollowPath.

Lua synopsis:
number deltaTimeLeft=simMoveToPosition(number objectHandle,number relativeToObjectHandle,table_3 position,table_3 orientation,number velocity,number acceleration,table_2 distanceCalculationMethod)

Lua parameters:
objectHandle: handle of the object to be moved
relativeToObjectHandle: indicates relative to which reference frame the movement should be performed. Specify -1 for a movement relative to the absolute reference frame, sim_handle_parent for a movement relative to the object's parent frame, or an object handle relative to whose reference frame the movement should be performed.
position: target position. Can be nil, in which case the current position is kept
orientation: target orientation (Euler angles). Can be nil, in which case the current orientation is kept
velocity: the target velocity for the movement. Velocity is relative to the specified distanceCalculationMethod
acceleration: the acceleration/deceleration. Can be nil in which case an infinite acceleration is applied
distanceCalculationMethod: a table containing: 1) The distance calculation method and 2) the angular to linear conversion coefficient. Can be nil in which case {sim_distcalcmethod_dl_if_nonzero,0.06366} is used. Refer to the path position calculation method section for more information.

Lua return values:
deltaTimeLeft: if the time needed to reach the position is not a multiple of the simulation time step, then deltatimeLeft is the execution time left at current simulation time. deltaTimeLeft is also memorized internally on a thread-basis and used as compensation or correction factor in subsequent blocking commands. deltaTimeLeft is nil in case of an error.

Cheers

Jay
Posts: 11
Joined: 14 Oct 2015, 16:34

Re: Yawing Bipedal Robot

Post by Jay »

Thank you for your quick reply. This is important to understand 'ant hexapod', then improve the codes by using 'simRMLMoveToPosition' instead.

Post Reply