Never changed ActorPlugin to Action, instead minor renaming and tweaks.
Updated launch file to support GPU-acceleration of the gazebo client. Created behavior tree for actor Updated robot urdf, added better visualization and colliders.
This commit is contained in:
@@ -14,6 +14,7 @@ find_package(ament_cmake REQUIRED)
|
||||
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY world DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY stl DESTINATION share/${PROJECT_NAME})
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
|
||||
@@ -14,11 +14,19 @@ def generate_launch_description():
|
||||
world_path = os.path.join(path, "world/test2.xml")
|
||||
urdf_path = os.path.join(path, "urdf/iisy.urdf")
|
||||
return LaunchDescription([
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
|
||||
launch_arguments={'world': world_path}.items()
|
||||
#IncludeLaunchDescription(
|
||||
# PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
|
||||
# launch_arguments={'world': world_path}.items()
|
||||
#),
|
||||
|
||||
ExecuteProcess(
|
||||
cmd=[[
|
||||
'LIBGL_ALWAYS_SOFTWARE=true ros2 launch gazebo_ros gzserver.launch.py "world:='+world_path+'"'
|
||||
]],
|
||||
shell=True
|
||||
),
|
||||
|
||||
|
||||
# Start Gazebo client
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py'))
|
||||
|
||||
BIN
src/gaz_simulation/stl/base_bottom_coll.stl
Executable file
BIN
src/gaz_simulation/stl/base_bottom_coll.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/base_bottom_low.stl
Executable file
BIN
src/gaz_simulation/stl/base_bottom_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/base_top_low.stl
Executable file
BIN
src/gaz_simulation/stl/base_top_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_1_full_coll.stl
Executable file
BIN
src/gaz_simulation/stl/link_1_full_coll.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_1_full_low.stl
Executable file
BIN
src/gaz_simulation/stl/link_1_full_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_2_bottom_low.stl
Executable file
BIN
src/gaz_simulation/stl/link_2_bottom_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_2_top_coll.stl
Executable file
BIN
src/gaz_simulation/stl/link_2_top_coll.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_2_top_low.stl
Executable file
BIN
src/gaz_simulation/stl/link_2_top_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_3_bottom_coll.stl
Executable file
BIN
src/gaz_simulation/stl/link_3_bottom_coll.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_3_bottom_low.stl
Executable file
BIN
src/gaz_simulation/stl/link_3_bottom_low.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_3_top_coll.stl
Executable file
BIN
src/gaz_simulation/stl/link_3_top_coll.stl
Executable file
Binary file not shown.
BIN
src/gaz_simulation/stl/link_3_top_low.stl
Executable file
BIN
src/gaz_simulation/stl/link_3_top_low.stl
Executable file
Binary file not shown.
@@ -1,195 +1,263 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="iisy" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<static>true</static>
|
||||
<link name='base'>
|
||||
<pose>0.025 0 0.05 0 0 0</pose>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<box size=".15 .1 .1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<box size=".15 .1 .1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="6"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="base_rot">
|
||||
<pose>0 0 0.155 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".11"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".11"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="link1">
|
||||
<pose>0 0 0.36 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".30"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".30"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.0325" ixy="0.0" ixz="0.0" iyy="0.0325" iyz="0.0" izz="0.005"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="link2_rot">
|
||||
<pose>0 0 0.585 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".15"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="link2">
|
||||
<pose>0 0 0.735 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".15"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="link3_rot">
|
||||
<pose>0 0 0.86 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".10"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".10"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0029166666666667" ixy="0.0" ixz="0.0" iyy="0.0029166666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="link3">
|
||||
<pose>0 0 0.94025 0 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".0605"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder radius=".05" length=".0605"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="0.8"/>
|
||||
<inertia ixx="0.00074401666666667" ixy="0.0" ixz="0.0" iyy="0.00074401666666667" iyz="0.0" izz="0.001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint type="continuous" name="base_rot_joint">
|
||||
<pose>0 0 -0.055 0 0 0</pose>
|
||||
<parent link="base"/>
|
||||
<child link="base_rot"/>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="iisy">
|
||||
<link name="world" />
|
||||
<link name="base_link"/>
|
||||
<link name="base">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_bottom_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0.025 0 0.05" rpy="0 0 0"/>
|
||||
<mass value="6"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="base_top">
|
||||
<collision>
|
||||
<origin xyz="0 -0.005 0.08"/>
|
||||
<geometry>
|
||||
<box size="0.14 0.15 0.16"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.155" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link1_full">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_1_full_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_1_full_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.36" rpy="0 0 0"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.0325" ixy="0.0" ixz="0.0" iyy="0.0325" iyz="0.0" izz="0.005"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link2_bottom">
|
||||
<collision>
|
||||
<origin xyz="0 0.07 0.025"/>
|
||||
<geometry>
|
||||
<box size="0.14 0.14 0.19"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.585" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link2_top">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_top_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.735" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link3_bottom">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_bottom_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.86" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0029166666666667" ixy="0.0" ixz="0.0" iyy="0.0029166666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link3_top">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_top_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.94025" rpy="0 0 0"/>
|
||||
<mass value="0.8"/>
|
||||
<inertia ixx="0.00074401666666667" ixy="0.0" ixz="0.0" iyy="0.00074401666666667" iyz="0.0" izz="0.001"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<joint type="fixed" name="world_base_link_fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base_link"/>
|
||||
</joint>
|
||||
<joint type="fixed" name="base_base_link_fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="base_rot">
|
||||
<origin xyz="0 0 0.1205" rpy="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="base_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="revolute" name="base_link1_joint">
|
||||
<origin xyz="0 -0.080499 0.092997" rpy="0 0 0"/>
|
||||
<parent link="base_top"/>
|
||||
<child link="link1_full"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-2.2689280275926" upper="2.4434609527921"/>
|
||||
</joint>
|
||||
<joint type="revolute" name="link1_link2_joint">
|
||||
<origin xyz="0 0 0.3" rpy="0 0 0"/>
|
||||
<parent link="link1_full"/>
|
||||
<child link="link2_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-2.6179938779915" upper="2.6179938779915"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link2_rot">
|
||||
<origin xyz="0 0.080501 0.120502" rpy="0 0 0"/>
|
||||
<parent link="link2_bottom"/>
|
||||
<child link="link2_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link2_link3_joint">
|
||||
<origin xyz="0 0.0565 0.178003" rpy="0 0 0"/>
|
||||
<parent link="link2_top"/>
|
||||
<child link="link3_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link3_rot">
|
||||
<origin xyz="0 -0.055001 0.085501" rpy="0 0 0"/>
|
||||
<parent link="link3_bottom"/>
|
||||
<child link="link3_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/simple_model</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<transmission name="trans_base_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="base_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<joint type="revolute" name="link1_joint">
|
||||
<pose>0 0 -0.15 0 0 0</pose>
|
||||
<parent link="base_rot"/>
|
||||
<child link="link1"/>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-1.221730476396" upper="1.221730476396"/>
|
||||
<actuator name="base_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_base_link1_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="base_link1_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<joint type="revolute" name="link2_rot_joint">
|
||||
<pose>0 0 -0.075 0 0 0</pose>
|
||||
<parent link="link1"/>
|
||||
<child link="link2_rot"/>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-1.3089969389957" upper="1.3089969389957"/>
|
||||
<actuator name="base_link1_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link1_link2_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link1_link2_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<joint type="continuous" name="link2_joint">
|
||||
<pose>0 0 -0.075 0 0 0</pose>
|
||||
<parent link="link2_rot"/>
|
||||
<child link="link2"/>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<actuator name="link1_link2_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link2_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link2_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<joint type="revolute" name="link3_rot_joint">
|
||||
<pose>0 0 -0.05 0 0 0</pose>
|
||||
<parent link="link2"/>
|
||||
<child link="link3_rot"/>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-0.95993108859688" upper="0.95993108859688"/>
|
||||
<actuator name="link2_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link2_link3_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link2_link3_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<joint type="continuous" name="link3_joint">
|
||||
<pose>0 0 -0.03025 0 0 0</pose>
|
||||
<parent link="link3_rot"/>
|
||||
<child link="link3"/>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<actuator name="link2_link3_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link3_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link3_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/simple_model</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</robot>
|
||||
<actuator name="link3_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</robot>
|
||||
@@ -111,7 +111,7 @@
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>-->
|
||||
<sensor name="laser" type="gpu_ray">
|
||||
<sensor name="laser_1" type="gpu_ray">
|
||||
<pose>0.1 0 0 0 0 0</pose>
|
||||
<ray>
|
||||
<scan>
|
||||
@@ -132,21 +132,21 @@
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>true</visualize>
|
||||
|
||||
<plugin name='laser' filename='libgazebo_ros_ray_sensor.so'>
|
||||
<plugin name='laser_1_plugin' filename='libgazebo_ros_ray_sensor.so'>
|
||||
<ros>
|
||||
<namespace>/lidar_1</namespace>
|
||||
<argument>--ros-args --remap ~/out:=scan</argument>
|
||||
</ros>
|
||||
<output_type>sensor_msgs/PointCloud2</output_type>
|
||||
</plugin>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</link>
|
||||
</model>
|
||||
<model name="lidar_2">
|
||||
<static>1</static>
|
||||
<link name="lidar_2_link">
|
||||
<pose>-2 1 1 0 0 </pose>
|
||||
<collision name='collision'>
|
||||
<pose>-1.9 1 1 0 0 </pose>
|
||||
<!--<collision name='collision'>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>.1 .1 .1</size>
|
||||
@@ -159,9 +159,8 @@
|
||||
<size>.1 .1 .1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="laser" type="gpu_ray">
|
||||
<pose>0.1 0 0 0 0 0</pose>
|
||||
</visual>-->
|
||||
<sensor name="laser_2" type="gpu_ray">
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
@@ -181,7 +180,7 @@
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>true</visualize>
|
||||
|
||||
<plugin name='laser' filename='libgazebo_ros_ray_sensor.so'>
|
||||
<plugin name='laser_2_plugin' filename='libgazebo_ros_ray_sensor.so'>
|
||||
<ros>
|
||||
<namespace>/lidar_2</namespace>
|
||||
<frameName>/lidar_2_link</frameName>
|
||||
|
||||
Reference in New Issue
Block a user