ros2中gazebo加载机器人的方式与ros1中有很大不同,一共有三种方式加载模型.
#使用-file 打开sdf文件
#使用-database需要先将模型路径添加到GAZEBO_MODEL_PATH ‘export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:model_path’ 而且模型需要参照gazebo中的标准写法才能成功加载
#使用-topic订阅机器人话题 话题由robot_state_publisher发布 其打开的是urdf文件
最后打开gazebo的.py文件如下:
import os
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import ThisLaunchFileDir
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from launch.actions import ExecuteProcess
from launch.substitutions import LaunchConfiguration
def generate_launch_description():
gazebo_dir = os.path.join(get_package_share_directory('gazebo_ros'),'launch')
# world = os.path.join(get_package_share_directory('gis_gazebo'), 'worlds', 'test.world')
urdf = os.path.join(
get_package_share_directory('gis_gazebo'),
'urdf','gis_car.urdf')
model_path = os.path.join(
get_package_share_directory('gis_gazebo'),
'models','pipe1.sdf')
use_sim_time = LaunchConfiguration('use_sim_time', default=True)
return LaunchDescription([
#退出gazebo时gzserver经常关不掉,所以打开gazebo前先关掉gzserver
ExecuteProcess(
cmd=['killall','-q', 'gzserver'],
output='screen'),
ExecuteProcess(
cmd=['killall','-q', 'gzclient'],
output='screen'),
IncludeLaunchDescription(
PythonLaunchDescriptionSource([gazebo_dir, '/gzserver.launch.py']),
# launch_arguments={
# 'world': world
# }.items(),
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource([gazebo_dir ,'/gzclient.launch.py'])),
#使用-file 打开sdf文件
#使用-database需要先将模型路径添加到GAZEBO_MODEL_PATH 'export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:model_path' 而且模型需要参照gazebo中的标准写法才能成功加载
#使用-topic订阅机器人话题 话题由robot_state_publisher发布 其打开的是urdf文件
Node(package='gazebo_ros', node_executable='spawn_entity.py',
arguments=[
'-x','0.0',
'-y','0.0',
'-z','2.0',
'-Y','0.0', #yaw
'-entity', 'car', #gazebo中机器命名
# '-database', 'cardboard_box',
# '-file',model_path,
'-topic','robot_description',
],
output='screen'),
Node(
package='robot_state_publisher',
node_executable='robot_state_publisher',
node_name='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'publish_frequency':100.0},
],
arguments=[urdf]
),
])
其中 world模型可以先打开gazebo,随意创建模型后另存为world.
urdf文件如下:
<?xml version ="1.0"?>
<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro"
name="ghost" >
<!-- Included URDF/XACRO Files -->
<!-- <xacro:include filename="$(find sick_scan)/urdf/example.urdf.xacro" /> -->
<link name="base_link">
<visual>
<geometry>
<box size="0.25 0.16 0.15"/>
</geometry>
<material name="sliver">
<color rgba="0.75 0.75 0.75 1"/>
</material>
</visual>
<!--碰撞大小-->
<collision>
<geometry>
<box size="0.25 0.16 0.15"/>
</geometry>
</collision>
<!--物理信息-->
<inertial>
<mass value="0.2"/>
<inertia ixx="0.5" iyy="0.75" izz="0.75"
ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<link name="fl_wheel">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black">
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.083" iyy="0.083" izz="0.0167"
ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<link name="fr_wheel">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black">
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.083" iyy="0.083" izz="0.0167"
ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<link name="bl_wheel">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black">
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.083" iyy="0.083" izz="0.0167"
ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<link name="br_wheel">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black">
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.083" iyy="0.083" izz="0.0167"
ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<joint name="fl_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="fl_wheel"/>
<origin rpy="-1.57 0 0" xyz="0.105 -0.0772 -0.05"/>
</joint>
<joint name="fr_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="fr_wheel"/>
<origin rpy="-1.57 0 0" xyz="0.105 0.0772 -0.05"/>
</joint>
<joint name="bl_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="bl_wheel"/>
<origin rpy="-1.57 0 0" xyz="-0.105 -0.0772 -0.05"/>
</joint>
<joint name="br_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="br_wheel"/>
<origin rpy="-1.57 0 0" xyz="-0.105 0.0772 -0.05"/>
</joint>
<!--添加激光传感器-->
<!--激光位置-->
<link name="scan_link">
</link>
<joint name="scan_joint" type="fixed">
<axis xyz=" 0 1 0"/>
<origin xyz="0.0 0.0 0.2" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="scan_link"/>
</joint>
<link name="imu_link">
</link>
<joint name="imu_joint" type="fixed">
<axis xyz=" 0 1 0"/>
<origin xyz="0.0 0.0 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="imu_link"/>
</joint>
<!--全向移动 -->
<gazebo>
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometryRate>100.0</odometryRate>
<robotBaseFrame>base_link</robotBaseFrame>
<broadcastTF>true</broadcastTF>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<!--<visualize>true</visualize>-->
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>imu</topicName>
<bodyName>base_link</bodyName>
<updateRateHZ>100.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu_link</frameName>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<!--激光雷达-->
<gazebo reference="scan_link">
<!--虚拟机无法使用GPU-->
<sensor type="ray" name="tim561">
<pose>0 0 0 0 0 0 </pose>
<visualize>true</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-2.093</min_angle>
<max_angle>2.093</max_angle>
</horizontal>
</scan>
<range>
<min>0.3</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.005</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_controller" filename="libgazebo_ros_laser.so">
<!--<plugin name="gpu_laser" filename="libgazebo_ros_laser.so">-->
<topicName>/scan</topicName>
<frameName>scan_link</frameName>
</plugin>
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<namespace>/test</namespace>
<remapping>joint_states:=joint_states_test</remapping>
</ros>
<update_rate>100</update_rate>
<joint_name>br_joint</joint_name>
<joint_name>bl_joint</joint_name>
<joint_name>fr_joint</joint_name>
<joint_name>fl_joint</joint_name>
</plugin>
</sensor>
</gazebo>
</robot>
sdf文件如下:
<?xml version="1.0" ?>
<sdf version="1.6">
<model name='lift_robot'>
<pose>0 0 0 0 0 0</pose>
<link name="base_footprint"/>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>1.14395</mass>
<inertia>
<ixx>0.126164</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.416519</iyy>
<iyz>0</iyz>
<izz>0.481014</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>2.4 1.2 2</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>2.4 1.2 2</size>
</box>
</geometry>
</collision>
</link>
<link name='bl_wheel'>
<pose>-1 -0.6 -1 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<link name='br_wheel'>
<pose>-1 0.6 -1 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<link name='fl_wheel'>
<pose>1 -0.6 -1 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<link name='fr_wheel'>
<pose>1 0.6 -1 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.35</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<link name='steering_wheel'>
<pose>1 0.6 -1 -1.5707 0 0</pose>
</link>
<joint name="base_joint" type="fixed">
<parent>base_footprint</parent>
<child>base_link</child>
<pose>0.0 0.0 0.00 0 0 0</pose>
</joint>
<joint name='fl_wheel_joint' type='universal'>
<parent>base_link</parent>
<child>fl_wheel</child>
</joint>
<joint name='fr_wheel_joint' type='universal'>
<parent>base_link</parent>
<child>fr_wheel</child>
</joint>
<!--全向轮设置 -->
<!-- <joint name='bl_wheel_joint' type='ball'>
<parent>base_link</parent>
<child>bl_wheel</child>
</joint>
<joint name='br_wheel_joint' type='ball'>
<parent>base_link</parent>
<child>br_wheel</child>
</joint> -->
<!-- 差速轮设置 -->
<joint name='bl_wheel_joint' type='revolute'>
<parent>base_link</parent>
<child>bl_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>
<joint name='br_wheel_joint' type='revolute'>
<parent>base_link</parent>
<child>br_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>
<joint name='steering_joint' type='revolute'>
<parent>base_link</parent>
<child>steering_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
<ros>
<argument>cmd_vel:=cmd_vel</argument>
<argument>odom:=odom</argument>
</ros>
<left_joint>br_wheel_joint</left_joint>
<right_joint>bl_wheel_joint</right_joint>
<wheel_separation>1.2</wheel_separation>
<wheel_diameter>0.7</wheel_diameter>
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>1.0</max_wheel_acceleration>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
<!-- <plugin name='planar_move' filename='libgazebo_ros_planar_move.so'>
<ros>
<argument>cmd_vel:=cmd_vel</argument>
<argument>odom:=odom</argument>
</ros>
<update_rate>100</update_rate>
<publish_rate>10</publish_rate>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<covariance_x>0.0001</covariance_x>
<covariance_y>0.0001</covariance_y>
<covariance_yaw>0.01</covariance_yaw>
</plugin> -->
<!-- <plugin name='ackermann_drive' filename='libgazebo_ros_ackermann_drive.so'>
<ros>
<argument>cmd_vel</argument>
<argument>odom</argument>
<argument>distance</argument>
</ros>
<update_rate>100.0</update_rate>
<front_left_joint>fl_wheel_joint</front_left_joint>
<front_right_joint>fr_wheel_joint</front_right_joint>
<rear_left_joint>bl_wheel_joint</rear_left_joint>
<rear_right_joint>br_wheel_joint</rear_right_joint>
<left_steering_joint>fl_wheel_joint</left_steering_joint>
<right_steering_joint>fr_wheel_joint</right_steering_joint>
<steering_wheel_joint>steering_joint</steering_wheel_joint>
<max_steer>0.6458</max_steer>
<max_steering_angle>7.85</max_steering_angle>
<max_speed>20</max_speed>
<left_steering_pid_gain>1500 0 1</left_steering_pid_gain>
<left_steering_i_range>0 0</left_steering_i_range>
<right_steering_pid_gain>1500 0 1</right_steering_pid_gain>
<right_steering_i_range>0 0</right_steering_i_range>
<linear_velocity_pid_gain>1000 0 1</linear_velocity_pid_gain>
<linear_velocity_i_range>0 0</linear_velocity_i_range>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
<publish_distance>true</publish_distance>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin> -->
<!--发布其它关节的位置信息-->
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<argument>joint_states:=joint_states</argument>
</ros>
<update_rate>30</update_rate>
<joint_name>br_wheel_joint</joint_name>
<joint_name>bl_wheel_joint</joint_name>
</plugin>
<link name="ray_link">
<pose>0 0 1.2 0 0 0</pose>
<visual name="visual_box">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
</visual>
<collision name="collision_box">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
<laser_retro>100.0</laser_retro>
</collision>
<!-- ray sensor -->
<sensor name="sensor_ray" type="ray">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>0.5</resolution>
<min_angle>-3.1415</min_angle>
<max_angle>3.1415</max_angle>
</horizontal>
<!-- <vertical>
<samples>100</samples>
<resolution>1.0</resolution>
<min_angle>-0.5236</min_angle>
<max_angle>0.5236</max_angle>
</vertical> -->
</scan>
<range>
<min>0.2</min>
<max>50.0</max>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/ray</namespace> -->
<argument>~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
</sensor>
</link>
<joint name='laser_joint' type='fixed'>
<parent>base_link</parent>
<child>ray_link</child>
</joint>
<link name="imu_link">
<sensor name="imu" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</z>
</linear_acceleration>
</imu>
<plugin name="imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<argument>~/out:=imu</argument>
</ros>
</plugin>
</sensor>
</link>
<joint name="imu_joint" type="fixed">
<parent>base_link</parent>
<child>imu_link</child>
<pose>0.0 0 0.0 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<link name="gps_link">
<pose>0 0 10 0 0 0</pose>
<sensor name="my_gps" type="gps">
<always_on>true</always_on>
<update_rate>30</update_rate>
<gps>
<position_sensing>
<horizontal>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</horizontal>
<vertical>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</vertical>
</position_sensing>
</gps>
<plugin name="gps_plugin" filename="libgazebo_ros_gps_sensor.so">
<ros>
<argument>~/out:=gps_data</argument>
</ros>
</plugin>
</sensor>
</link>
<joint name="gps_joint" type="fixed">
<parent>base_link</parent>
<child>gps_link</child>
</joint>
</model>
</sdf>