文章目录
写在前面的话
在 gazebo 上进行仿真建模的时候,有时候需要发布动态的障碍或者动态的指示箭头,这样可以直接在 gazebo 上很直观的显示,相关的函数接口肯定是有的,但是网上相关的内容的信息很少,尤其中文网站,想着还是要写一篇分享一下。
实现步骤
1 构建sdf模型
注意事项:需要把 static 属性设置为0,也就是不能是静态,而且要设置碰撞体积 collision,否则物体会在重力作用下一直下坠,z轴会越来越大,不想物体受到重力效果的话就把 gravity 属性设置为0。
sdf 文件内容示例
gazebo 有很多官方的模型库,但是不能调整外观参数,矩形、圆柱等简单的模型可以根据需要自己调整尺寸颜色。
<?xml version='1.0'?>
<sdf version='1.7'>
<model name='direction_line'>
<link name='link_5'>
<inertial>
<mass>1.0</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
<pose>0 0 0 0 -0 0</pose>
</inertial>
<pose>0 0 0 0 -0 0</pose>
<gravity>0</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<enable_wind>0</enable_wind>
<visual name='visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.5 20 0.1</size>
</box>
</geometry>
<material>
<lighting>1</lighting>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
<shader type='pixel'>
<normal_map>__default__</normal_map>
</shader>
<ambient>1 0.9 0 1</ambient>
<diffuse>1 0.7 0.7 1</diffuse>
<specular>0.31 0.01 0.01 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<transparency>0</transparency>
<cast_shadows>1</cast_shadows>
</visual>
</link>
<static>0</static>
<allow_auto_disable>1</allow_auto_disable>
</model>
</sdf>
gazebo 菜单栏的 Edit 的 Model Editor 选项
2 修改 .world 文件(非常关键)
需要在gazebo启动的world文件里面加入 libgazebo_ros_state.so 插件,否则模型根本无法通过命令移动
核心代码
<plugin name="gazebo_ros_state" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
<update_rate>1.0</update_rate>
</plugin>
参考链接:
1 How to use gazebo plugins found in gazebo_ros [ROS2 Foxy gazebo11]
2 /gazebo/get_model_state in ROS2 not present
3 ROS2 Dashing service get_entity_state
is missing
图片示例
3 物体发布代码(python)
这个代码的作用是把物体模型发布到 gazebo 中,模型名称为 dl,发布成功会输出生成成功,模型会在 gazebo 中显示,这个也可以开始就跟随地图一起加载显示。
# spawn_model.py
import rclpy
from rclpy.node import Node
from gazebo_msgs.srv import SpawnEntity
from geometry_msgs.msg import Pose
class ModelSpawner(Node):
def __init__(self):
super().__init__('model_spawner')
self.client = self.create_client(SpawnEntity, 'spawn_entity')
while not self.client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('等待spawn_entity服务...')
def spawn_model(self, model_name, xml, pose):
req = SpawnEntity.Request()
req.name = model_name
req.xml = xml
req.initial_pose = pose
future = self.client.call_async(req)
rclpy.spin_until_future_complete(self, future)
if future.result() is not None:
self.get_logger().info(f'模型 {
model_name} 生成成功!')
else:
self.get_logger().error(f'生成模型失败: {
future.exception()}')
def main():
rclpy.init()
spawner = ModelSpawner()
with open('/home/gg/xcg-2025/direction_line/model.sdf', 'r') as f:
xml = f.read()
initial_pose = Pose()
initial_pose.position.x = 0.5
initial_pose.position.y = 0.5
initial_pose.position.z = 0.5
initial_pose.orientation.w = 1.0
spawner.spawn_model('dl', xml, initial_pose)
rclpy.shutdown()
if __name__ == '__main__':
main()
发布的模型在 gazebo 中显示
4 终端快速验证
1 验证命令
ros2 service call /gazebo/set_entity_state gazebo_msgs/SetEntityState "state: {name: dl, pose: {position:{x: 6.5, y: 0.0, z: 10.0}}, reference_frame: world}"
2 终端输出
gg@gg:~/xcg-2025$ ros2 service call /gazebo/set_entity_state gazebo_msgs/SetEntityState "state: {name: dl, pose: {position:{x: 6.5, y: 0.0, z: 10.0}}, reference_frame: world}"
requester: making request: gazebo_msgs.srv.SetEntityState_Request(state=gazebo_msgs.msg.EntityState(name='dl', pose=geometry_msgs.msg.Pose(position=geometry_msgs.msg.Point(x=6.5, y=0.0, z=10.0), orientation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)), twist=geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0)), reference_frame='world'))
response:
gazebo_msgs.srv.SetEntityState_Response(success=True)
5 物体移动代码(python)
ROS1 和 ROS2 命令对比(gazebo 物体状态)
参考链接:ROS 2 Migration: Entity states
完整代码
代码功能是让物体进行循环圆周运动,可以根据自己要求自己修改
# move_entity.py
import rclpy
from rclpy.node import Node
from gazebo_msgs.srv import SetEntityState
from geometry_msgs.msg import Pose, Point, Quaternion
import math
class EntityMover(Node):
def __init__(self):
super().__init__('entity_mover')
self.cli = self.create_client(SetEntityState, '/gazebo/set_entity_state')
self.theta = 0.0
self.timer = self.create_timer(0.1, self.send_request)
# 等待服务可用
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('等待服务 /gazebo/set_entity_state ...')
def send_request(self):
# 构造请求消息
req = SetEntityState.Request()
# 填充 EntityState 数据
req.state.name = "dl" # 模型名称
# 圆形轨迹参数
radius = 10.0
angular_speed = 0.1
self.theta += angular_speed
# 更新位置
req.state.pose.position.x = radius * math.sin(self.theta)
req.state.pose.position.y = radius * math.cos(self.theta)
req.state.pose.position.z = 1.0
req.state.pose.orientation = Quaternion(w=1.0)
# 设置位姿
# req.state.pose = Pose()
# req.state.pose.position = Point(x=1.0, y=0.0, z=1.0)
# req.state.pose.orientation = Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)
# 设置参考坐标系
req.state.reference_frame = "world"
# 可选:设置速度(如果需要)
# req.state.twist.linear.x = 0.5
# 发送异步请求
self.future = self.cli.call_async(req)
# self.get_logger().info('请求已发送,等待响应...')
self.get_logger().info(f'移动模型到: {
req.state.pose.position}')
def main(args=None):
rclpy.init(args=args)
mover = EntityMover()
mover.send_request()
rclpy.spin(mover)
# # 等待响应
# rclpy.spin_until_future_complete(mover, mover.future)
# # 处理结果
# if mover.future.result() is not None:
# response = mover.future.result()
# if response.success:
# mover.get_logger().info('操作成功!')
# else:
# mover.get_logger().error(f'操作失败: {response.status_message}')
# else:
# mover.get_logger().error('服务调用失败')
mover.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
视频演示
gazebo ros2 设置动态物体