| ²é¿´: 2600 | »Ø¸´: 7 | |||
| µ±Ç°Ö»ÏÔʾÂú×ãÖ¸¶¨Ìõ¼þµÄ»ØÌû£¬µã»÷ÕâÀï²é¿´±¾»°ÌâµÄËùÓлØÌû | |||
szb21971Òø³æ (ÕýʽдÊÖ)
|
[ÇóÖú]
Ë«×ã»úÆ÷ÈËÐÐ×ß¹÷ͼÔõôÓÃMATLAB»³öÀ´°¡£¿ÇóÖú°¡£¡£¡£¡ ÒÑÓÐ1È˲ÎÓë
|
||
| Ë«×ã»úÆ÷ÈËÐÐ×ß¹÷ͼÔõôÓÃMATLAB»³öÀ´°¡£¿ÇóÖú°¡£¡£¡£¡ |
» ²ÂÄãϲ»¶
284Çóµ÷¼Á
ÒѾÓÐ10È˻ظ´
һ־Ըɽ¶«´óѧҩѧѧ˶Çóµ÷¼Á
ÒѾÓÐ4È˻ظ´
07»¯Ñ§280·ÖÇóµ÷¼Á
ÒѾÓÐ4È˻ظ´
298-Ò»Ö¾Ô¸Öйúũҵ´óѧ-Çóµ÷¼Á
ÒѾÓÐ12È˻ظ´
Çó²ÄÁÏ£¬»·¾³×¨Òµµ÷¼Á
ÒѾÓÐ3È˻ظ´
335Çóµ÷¼Á
ÒѾÓÐ5È˻ظ´
Çóµ÷¼Á
ÒѾÓÐ7È˻ظ´
Ò»Ö¾Ô¸¼ª´ó»¯Ñ§322Çóµ÷¼Á
ÒѾÓÐ4È˻ظ´
»·¾³Ñ§Ë¶288Çóµ÷¼Á
ÒѾÓÐ8È˻ظ´
341Çóµ÷¼Á(Ò»Ö¾Ô¸ºþÄÏ´óѧ070300)
ÒѾÓÐ6È˻ظ´

blackwave
Ìú³æ (³õÈëÎÄ̳)
- Ó¦Öú: 0 (Ó×¶ùÔ°)
- ½ð±Ò: 40.7
- Ìû×Ó: 26
- ÔÚÏß: 12.8Сʱ
- ³æºÅ: 184462
- ×¢²á: 2006-02-14
- ÐÔ±ð: GG
- רҵ: »úÆ÷ÈËѧ¼°»úÆ÷È˼¼Êõ
¡¾´ð°¸¡¿Ó¦Öú»ØÌû
¡ï ¡ï ¡ï ¡ï ¡ï ¡ï ¡ï ¡ï ¡ï ¡ï
szb21971: ½ð±Ò+10, ¡ïÓаïÖú 2015-01-19 09:46:24
szb21971: ½ð±Ò+10, ¡ïÓаïÖú 2015-01-19 09:46:24
|
The following is a function I wrote to generate a stick diagram of robot motion. Hope it is helpful to you all. function [foot2] = stick(filename,user_frame_per_second,max_step) global robot foot2=[]; mov_traj = load(filename); dt = mov_traj(2,1) - mov_traj(1,1); frame_per_second = fix(1/dt); if user_frame_per_second == 0 show_frame_per_second = frame_per_second; else show_frame_per_second = user_frame_per_second; end capture_frame_per_second = 20; color0 = [0 0 0]; color1 = [0 0 0]; color2 = [0 0 0]; color3 = [1 1 1]*0.5; color4 = [1 1 1]*0.5; width = 2; scrsz = get(0,'ScreenSize'); animation = figure; %hold on xxlim = [-0.8 0.8] yylim = [ 0.0 1.6] set(animation,'name','2D walking','Position',[100 100 450 450]); h_axes = axes('Parent',animation,'Units','Pixels','Position',[50 40 400 400],'Ylim',yylim,'Xlim',xxlim); %tx = text('Parent',h_axes,'Visible','off'); set(h_axes,'visible','on'); ground = line('Parent',h_axes,'Color',[0 0 0],'Visible','off','LineWidth',2); set(ground, 'Parent',h_axes,'Xdata',xxlim,'Ydata', [0 0],'visible','on'); idx =1 ss_flag = 0; step_count = 0; l_ankle_pos = zeros(2,1); l_knee_pos = zeros(2,1); l_hip_pos = zeros(2,1); head_pos = zeros(2,1); r_knee_pos = zeros(2,1); r_ankle_pos = zeros(2,1); r_ankle_pos_b_save = [-1,0]'; base = [0 0]'; for i = 1:size(mov_traj,1) tt = mov_traj(i,1); l_ankle_abs = mov_traj(i,2); l_knee_abs = l_ankle_abs + mov_traj(i,3); l_hip_abs = l_knee_abs + mov_traj(i,4); r_hip_abs = l_hip_abs + mov_traj(i,5); r_knee_abs = r_hip_abs + mov_traj(i,6); % r_knee_abs = r_knee_abs; l_ankle_pos_b =[0 0]'; l_knee_pos_b = [ -robot.calf_length * sin(l_ankle_abs) robot.calf_length* cos(l_ankle_abs)]'; l_hip_pos_b = [l_knee_pos_b(1)-sin(l_knee_abs)*robot.thigh_length l_knee_pos_b(2)+cos(l_knee_abs)*robot.thigh_length ]'; head_pos_b = [l_hip_pos_b(1)-sin(l_hip_abs)*robot.torso_length l_hip_pos_b(2) + cos(l_hip_abs)*robot.torso_length]'; r_knee_pos_b = [l_hip_pos_b(1)+sin(r_hip_abs)*robot.thigh_length l_hip_pos_b(2) - cos(r_hip_abs)*robot.thigh_length]'; r_ankle_pos_b = [r_knee_pos_b(1)+sin(r_knee_abs)*robot.calf_length r_knee_pos_b(2) - cos(r_knee_abs)*robot.calf_length]'; if (r_ankle_pos_b_save(1) > 0 && r_ankle_pos_b(1) < 0) % switch step_count = step_count +1; if step_count >= max_step break end ss_flag = 1; tmp = color0; color0 = color4; color4=tmp; tmp = color1; color1 = color3; color3=tmp; set(l_calf,'Color',color0,'Visible','off'); set(l_thigh,'Color',color1,'Visible','off'); set(torso,'Color',color2,'Visible','off') set(r_thigh,'Color',color3,'Visible','off'); set(r_calf,'Color',color4,'Visible','off'); % hip_travel = hip_travel + r_ankle_pos_b_save(1); % ground_height = ground_height + r_ankle_pos_b_save(2); base = base + r_ankle_pos_b_save; %ground_height =0 ; %set(h_axes,'Ylim',[-0.05+ground_height 1.95+ground_height]); base; r_ankle_pos_b_save; r_ankle_pos_b; %pause end r_ankle_pos_b_save = r_ankle_pos_b; % drift = l_hip_pos(1); % l_ankle_pos(1) = l_ankle_pos(1) - drift; % l_knee_pos(1) = l_knee_pos(1) - drift; % l_hip_pos(1) = l_hip_pos(1) - drift; % head_pos(1) = head_pos(1) - drift; % r_knee_pos(1) = r_knee_pos(1) - drift; % r_ankle_pos(1) = r_ankle_pos(1) - drift; l_ankle_pos = l_ankle_pos_b + base; l_knee_pos = l_knee_pos_b + base; l_hip_pos = l_hip_pos_b + base; head_pos = head_pos_b + base; r_knee_pos = r_knee_pos_b + base; r_ankle_pos = r_ankle_pos_b + base; foot2 = [foot2,r_ankle_pos]; if (mod(i,fix(frame_per_second/show_frame_per_second)) == 1 ) torso = line('Parent',h_axes,'Color',color2,'Visible','off','LineWidth',width); r_thigh = line('Parent',h_axes,'Color',color3,'Visible','off','LineWidth',width); r_calf = line('Parent',h_axes,'Color',color4,'Visible','off','LineWidth',width); l_calf = line('Parent',h_axes,'Color',color0,'Visible','off','LineWidth',width); l_thigh = line('Parent',h_axes,'Color',color1,'Visible','off','LineWidth',width); if mod(step_count,2) == 1 set(l_calf, 'Parent',h_axes,'Xdata',[l_ankle_pos(1) l_knee_pos(1)],'Ydata', [l_ankle_pos(2) l_knee_pos(2)],'visible','on'); set(l_thigh, 'Parent',h_axes,'Xdata',[l_knee_pos(1) l_hip_pos(1)],'Ydata', [l_knee_pos(2) l_hip_pos(2)],'visible','on'); set(torso, 'Parent',h_axes,'Xdata',[l_hip_pos(1) head_pos(1)],'Ydata', [l_hip_pos(2) head_pos(2)],'visible','on'); set(r_thigh, 'Parent',h_axes,'Xdata',[l_hip_pos(1) r_knee_pos(1)],'Ydata', [l_hip_pos(2) r_knee_pos(2)],'visible','on'); set(r_calf, 'Parent',h_axes,'Xdata',[r_knee_pos(1) r_ankle_pos(1)],'Ydata', [r_knee_pos(2) r_ankle_pos(2)],'visible','on'); else set(torso, 'Parent',h_axes,'Xdata',[l_hip_pos(1) head_pos(1)],'Ydata', [l_hip_pos(2) head_pos(2)],'visible','on'); set(r_thigh, 'Parent',h_axes,'Xdata',[l_hip_pos(1) r_knee_pos(1)],'Ydata', [l_hip_pos(2) r_knee_pos(2)],'visible','on'); set(r_calf, 'Parent',h_axes,'Xdata',[r_knee_pos(1) r_ankle_pos(1)],'Ydata', [r_knee_pos(2) r_ankle_pos(2)],'visible','on'); set(l_calf, 'Parent',h_axes,'Xdata',[l_ankle_pos(1) l_knee_pos(1)],'Ydata', [l_ankle_pos(2) l_knee_pos(2)],'visible','on'); set(l_thigh, 'Parent',h_axes,'Xdata',[l_knee_pos(1) l_hip_pos(1)],'Ydata', [l_knee_pos(2) l_hip_pos(2)],'visible','on'); end stime=sprintf('time:%5.2f',tt); %set(tx,'Parent',h_axes,'Position',[l_hip_pos(1),1.8],'String',stime,'visible','on'); %set(h_axes,'Xlim',[l_hip_pos(1)-1.0 l_hip_pos(1)+1.0]); drawnow; end if l_ankle_pos(1) > xxlim(2) break end end xlabel('(m)') ylabel('(m)') |
7Â¥2015-01-15 11:38:18
szb21971
Òø³æ (ÕýʽдÊÖ)
- Ó¦Öú: 4 (Ó×¶ùÔ°)
- ½ð±Ò: 5882
- É¢½ð: 260
- ºì»¨: 5
- Ìû×Ó: 912
- ÔÚÏß: 142.8Сʱ
- ³æºÅ: 1504810
- ×¢²á: 2011-11-22
- ÐÔ±ð: GG
- רҵ: »úÆ÷ÈËѧ¼°»úÆ÷È˼¼Êõ

2Â¥2015-01-11 11:14:47
szb21971
Òø³æ (ÕýʽдÊÖ)
- Ó¦Öú: 4 (Ó×¶ùÔ°)
- ½ð±Ò: 5882
- É¢½ð: 260
- ºì»¨: 5
- Ìû×Ó: 912
- ÔÚÏß: 142.8Сʱ
- ³æºÅ: 1504810
- ×¢²á: 2011-11-22
- ÐÔ±ð: GG
- רҵ: »úÆ÷ÈËѧ¼°»úÆ÷È˼¼Êõ

3Â¥2015-01-11 11:15:36
sichanglong
Ìú³æ (СÓÐÃûÆø)
- Ó¦Öú: 8 (Ó×¶ùÔ°)
- ½ð±Ò: 151.7
- É¢½ð: 50
- Ìû×Ó: 98
- ÔÚÏß: 28.5Сʱ
- ³æºÅ: 2080488
- ×¢²á: 2012-10-23
- ÐÔ±ð: GG
- רҵ: µ¼º½¡¢ÖƵ¼Óë´«¸Ð¼¼Êõ

4Â¥2015-01-11 16:20:18













»Ø¸´´ËÂ¥