Gazebo自带的一些模型,比如人行走和奔跑的模型,在/usr/share/gazebo-11/media/models
。Gazebo的行人模型不是障碍,机器人开过去撞不上,Rviz里也不会作为障碍,只能找插件让它变成障碍。
Gazebo模型碰撞的插件actor_collisions,按照说明进行编译后,如果执行gazebo ../actor_collisions.world
正常,那么说明安装成功了。然后将libActorCollisionsPlugin.so
文件复制到/opt/ros/noetic/lib
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
| <actor name="actor"> <plugin name="actor_collisions_plugin" filename="libActorCollisionsPlugin.so"> <scaling collision="LHipJoint_LeftUpLeg_collision" scale=" 0.01 0.001 0.001 "/> ...... <scaling collision="RightFingerBase_RightHandIndex1_collision" scale=" 4.0 4.0 3.0 "/> </plugin>
|
1 2 3 4 5 6 7 8 9 10 11 12 13
| <pose>3 -3 0.9 1.57 0 0</pose>
<skin> <filename>walk.dae</filename> <scale>1.0</scale> </skin>
<animation name="walking"> <filename>walk.dae</filename> <scale>1.000000</scale> <interpolate_x>true</interpolate_x> </animation>
|
循环行走的逻辑,使用script
,手动确定每个时间点的位姿,尽量保证循环行走的平滑性。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21
| <script> <loop>true</loop> <delay_start>0.000000</delay_start> <auto_start>true</auto_start>
<trajectory id="0" type="walking"> <waypoint> <time>0.000000</time> <pose>0.000000 1.000000 0.000000 0.000000 0.000000 0.000000</pose> </waypoint> <waypoint> <time>0.500000</time> <pose>0.195090 0.980785 0.000000 0.000000 0.000000 -0.196350</pose> </waypoint> ...... <waypoint> <time>18.000000</time> <pose>-0.195090 0.980785 0.000000 0.000000 0.000000 0.196345</pose> </waypoint> </trajectory> </script>
|
插件的缺点:
- 插件的
collision
参数难以准确设置
- 行走的时间和位姿难以保证平滑性
第1个缺点不好解决,不同的模型需要单独设置参数。针对第2个缺点,我发现了插件gazebo_ros_actor_plugin,这个插件可以对行人进行速度控制。
两种模式(follow_mode
): velocity
模式,使用teleop_twist_keyboard
进行手动控制; path
模式,按照path_publisher.py
指定路径行走。
对于可控制actor移动的模式,world
文件加入下面内容
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27
| <actor name="actor"> <pose>3 -3 0.9 1.57 0 0</pose>
<skin> <filename>walk.dae</filename> <scale>1.0</scale> </skin>
<animation name="walking"> <filename>walk.dae</filename> <scale>1.000000</scale> <interpolate_x>true</interpolate_x> </animation>
<plugin name="actor_plugin" filename="libgazebo_ros_actor_command.so"> <follow_mode>velocity</follow_mode> <vel_topic>/gazebo_cmd_vel</vel_topic> <path_topic>/cmd_path</path_topic> <animation_factor>4.0</animation_factor> <linear_tolerance>0.1</linear_tolerance> <linear_velocity>1</linear_velocity> <angular_tolerance>0.0872</angular_tolerance> <angular_velocity>2.5</angular_velocity> <default_rotation>1.57</default_rotation> </plugin> </actor>
|
但问题在于,这个插件的行人和默认的一样,
不是障碍,如果能将两个插件结合就好了。
但是同时加载两个插件后,Gazebo里的行人不能正常显示,要么是频繁在站立和躺着之间切换,要么就是原地走,但没有往前动。如果旋转,行人没反应。显然是两个插件冲突了。
修改
将第1个插件的Load
函数加入第2个插件,再把SetWorldPose
函数的后两个参数从false改为true,即 this->actor_->SetWorldPose(pose, true, true);
,编译之后把生成的libgazebo_actor_cmd_collision.so
放入/usr/lib/x86_64-linux-gnu/gazebo-11/plugins
这样把两个插件合并,可以让actor作为障碍被用户控制。
如果配置Gazebo有多个actor,可以都设置为手动控制模式,只要话题名不同,也能分别控制。
缺点: 不同actor不会相撞,遇到时会穿过。
也可以设置有的actor为手动控制模式,有的为路径模式。

最终效果.gif