Browse Source

Merge branch 'dev/noetic' of github.com:hello-robot/stretch_ros into dev/noetic

merged files
pull/34/head
nwright 3 years ago
parent
commit
c07a6224e5
3 changed files with 91 additions and 38 deletions
  1. +7
    -4
      stretch_gazebo/launch/gazebo.launch
  2. +10
    -1
      stretch_gazebo/scripts/publish_ground_truth_odom.py
  3. +74
    -33
      stretch_gazebo/urdf/stretch_gazebo.urdf.xacro

+ 7
- 4
stretch_gazebo/launch/gazebo.launch View File

@ -1,15 +1,18 @@
<launch> <launch>
<arg name="paused" default="false"/>
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/> <arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/> <arg name="gui" default="true"/>
<arg name="headless" default="false"/> <arg name="headless" default="false"/>
<arg name="debug" default="false"/> <arg name="debug" default="false"/>
<arg name="rviz" default="false"/> <arg name="rviz" default="false"/>
<arg name="model" default="$(find stretch_gazebo)/urdf/stretch_gazebo.urdf.xacro"/> <arg name="model" default="$(find stretch_gazebo)/urdf/stretch_gazebo.urdf.xacro"/>
<arg name="gpu_lidar" default="false"/>
<arg name="visualize_lidar" default="false"/>
<arg name="world" default="worlds/empty.world"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch"> <include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="/usr/share/gazebo-11/worlds/willowgarage.world"/>
<arg name="world_name" value="$(arg world)" />
<arg name="debug" value="$(arg debug)" /> <arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" /> <arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/> <arg name="paused" value="$(arg paused)"/>
@ -18,11 +21,11 @@
<arg name="verbose" value="true"/> <arg name="verbose" value="true"/>
</include> </include>
<param name="robot_description" command="$(find xacro)/xacro $(arg model)" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model) gpu_lidar:=$(arg gpu_lidar) visualize_lidar:=$(arg visualize_lidar)" />
<!-- push robot_description to factory and spawn robot in gazebo --> <!-- push robot_description to factory and spawn robot in gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
args=" -urdf -model robot -param robot_description" respawn="false" output="screen" />
args=" -urdf -model robot -param robot_description -J joint_lift 0.2 -J joint_wrist_yaw 3.14" respawn="false" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="30.0" /> <param name="publish_frequency" type="double" value="30.0" />

+ 10
- 1
stretch_gazebo/scripts/publish_ground_truth_odom.py View File

@ -3,14 +3,17 @@
from gazebo_msgs.srv import GetModelState, GetModelStateRequest, GetWorldProperties from gazebo_msgs.srv import GetModelState, GetModelStateRequest, GetWorldProperties
from nav_msgs.msg import Odometry from nav_msgs.msg import Odometry
from std_msgs.msg import Header from std_msgs.msg import Header
from std_srvs.srv import Empty
import rospy import rospy
import time
rospy.init_node('ground_truth_odometry_publisher') rospy.init_node('ground_truth_odometry_publisher')
odom_pub=rospy.Publisher('ground_truth', Odometry, queue_size=10) odom_pub=rospy.Publisher('ground_truth', Odometry, queue_size=10)
rospy.wait_for_service ('/gazebo/get_model_state')
rospy.wait_for_service('/gazebo/get_model_state')
get_model_srv = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState) get_model_srv = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState)
get_world_properties = rospy.ServiceProxy('/gazebo/get_world_properties', GetWorldProperties) get_world_properties = rospy.ServiceProxy('/gazebo/get_world_properties', GetWorldProperties)
unpause_physics = rospy.ServiceProxy('/gazebo/unpause_physics', Empty)
odom=Odometry() odom=Odometry()
header = Header() header = Header()
@ -20,6 +23,12 @@ model.model_name='robot'
models = [] models = []
r = rospy.Rate(20) r = rospy.Rate(20)
pause_timeout = time.time() + 4.0
while time.time() < pause_timeout:
rospy.logwarn("Waiting %.2f seconds to unpause physics", pause_timeout - time.time())
time.sleep(1.0)
unpause_physics()
while not rospy.is_shutdown(): while not rospy.is_shutdown():
if model.model_name not in models: if model.model_name not in models:
models = get_world_properties().model_names models = get_world_properties().model_names

+ 74
- 33
stretch_gazebo/urdf/stretch_gazebo.urdf.xacro View File

@ -1,5 +1,8 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_description"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_description">
<xacro:arg name="gpu_lidar" default="false" />
<xacro:arg name="visualize_lidar" default="false" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_main.xacro" /> <xacro:include filename="$(find stretch_description)/urdf/stretch_main.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_aruco.xacro" /> <xacro:include filename="$(find stretch_description)/urdf/stretch_aruco.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_d435i.xacro" /> <xacro:include filename="$(find stretch_description)/urdf/stretch_d435i.xacro" />
@ -237,39 +240,77 @@
<material>Gazebo/Green</material> <material>Gazebo/Green</material>
</gazebo> </gazebo>
<!-- LIDAR -->
<gazebo reference="laser">
<material>Gazebo/Black</material>
<sensor type="gpu_ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>2000</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
</scan>
<range>
<min>0.5</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
<!-- Non GPU LIDAR -->
<xacro:unless value="$(arg gpu_lidar)">
<gazebo reference="laser">
<material>Gazebo/Black</material>
<sensor type="ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg visualize_lidar)</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>2000</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:unless>
<!-- GPU LIDAR -->
<xacro:if value="$(arg gpu_lidar)">
<gazebo reference="laser">
<material>Gazebo/Black</material>
<sensor type="gpu_ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg visualize_lidar)</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>2000</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:if>
<!-- Base IMU --> <!-- Base IMU -->
<gazebo reference="base_link"> <gazebo reference="base_link">

Loading…
Cancel
Save