##040003119487738000005
*
* Compile mechanism for sm_nj_290_30
*
begin COMPONENT sm_nj_290_30
	no_of_joints		12
	no_of_loops		2
	TCP_link_name		k7
	user_TCP :
0	0	1	2251.999268	
0	1	0	0	
-1	0	0	2440	
0	0	0	1	
	inverse_family	-1
	base_name		k1

	begin LINK k2
		joint_from	k1
		transformation_to_father :
1	0	0	0	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j1
		axis_points	0 0 1000 , 0 0 0
		param_index	0
		joint_type	rot
		user_value	0
		range		-180 180
		max_speed	90
		max_acceleration	90
	end;

	begin LINK k3
		joint_from	k2
		transformation_to_father :
1	0	0	0.00058	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j2
		axis_points	460 -1000 1140 , 460 1000 1140
		param_index	1
		joint_type	rot
		user_value	0
		dependent range on joint	j3
		extreme		-81	-75 ;
		extreme		0	-75 ;
		extreme		0	-30 ;
		extreme		-105	75 ;
		extreme		-220	75 ;
		extreme		-220	64
		max_speed	90
		max_acceleration	90
	end;

	begin LINK k4
		joint_from	k3
		transformation_to_father :
0	0	-1	2650	
0	1	0	0	
1	0	0	1729.998779	
0	0	0	1	
		joint_name	j3
		axis_points	460 1000 2190 , 460 -1000 2190
		param_index	2
		follows j2 by 1
		joint_type	rot
		user_value	0
		dependent range on joint	j2
		extreme		-75	-81 ;
		extreme		-75	0 ;
		extreme		-30	0 ;
		extreme		75	-105 ;
		extreme		75	-220 ;
		extreme		64	-220
		max_speed	90
		max_acceleration	90
	end;

	begin LINK k5
		joint_from	k4
		transformation_to_father :
1	0	0	-0.000122	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j4
		axis_points	0 0 2440 , -1000 0 2440
		param_index	3
		joint_type	rot
		user_value	0
		range		-2700 2700
		max_speed	90
		max_acceleration	90
	end;

	begin LINK k6
		joint_from	k5
		transformation_to_father :
1	0	0	-0.000488	
0	1	0	0	
0	0	1	0.000732	
0	0	0	1	
		joint_name	j5
		axis_points	1970 -1000 2440 , 1970 1000 2440
		param_index	4
		joint_type	rot
		user_value	0
		range		-125 125
		max_speed	90
		max_acceleration	90
	end;

	begin LINK k7
		joint_from	k6
		transformation_to_father :
1	0	0	0	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j6
		axis_points	3305 0 2440 , 2305 0 2440
		param_index	5
		joint_type	rot
		user_value	0
		range		-2700 2700
		max_speed	90
		max_acceleration	90
	end;

	begin LINK l1va
		joint_from	k4
		transformation_to_father :
0	0	1	-2130	
0	1	0	0	
-1	0	0	2250.002441	
0	0	0	1	
		joint_name	j10
		axis_points	60 1000 2190 , 60 -100 2190
		param_index	6
		joint_type	rot
		user_value	0
		range		no limits
		max_speed	90
		max_acceleration	90
	end;

	begin LINK bil
		joint_from	l1va
		transformation_to_father :
0	0	-1	1199.997803	
0	1	0	0	
1	0	0	1079.998047	
0	0	0	1	
		joint_name	j11
		axis_points	60 1000 1140 , 60 -100 1140
		param_index	7
		joint_type	rot
		user_value	0
		range		no limits
		max_speed	90
		max_acceleration	90
	end;

	begin LINK msup
		joint_from	k3
		transformation_to_father :
1	0	0	-0.001578	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j7
		axis_points	460 1000 2190 , 460 1100 2190
		param_index	8
		joint_type	rot
		user_value	0
		range		no limits
		max_speed	90
		max_acceleration	90
	end;

	begin LINK minf
		joint_from	msup
		transformation_to_father :
1	0	0	0	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j8
		axis_points	460 1050 2190 , 460 1050 1327
		param_index	9
		joint_type	prism
		user_value	0
		range		no limits
		max_speed	1000
		max_acceleration	1000
	end;

	begin CLOSE_LOOP k2
		joint_from	bil
		transformation_to_father :
0	0	1	-679.996948	
0	1	0	0	
-1	0	0	1599.99585	
0	0	0	1	
		joint_name	j12
		axis_points	460 -1000 1140 , 460 1000 1140
		param_index	10
		joint_type	rot
		user_value	0
		range		no limits
		max_speed	90
		max_acceleration	90
	end;

	begin CLOSE_LOOP k2
		joint_from	minf
		transformation_to_father :
1	0	0	0.000999	
0	1	0	0	
0	0	1	0	
0	0	0	1	
		joint_name	j9
		axis_points	460 1000 1327 , 460 1100 1327
		param_index	11
		joint_type	rot
		user_value	0
		range		no limits
		max_speed	90
		max_acceleration	90
	end

end
