Added urdf
This commit is contained in:
parent
a1a54f58e4
commit
1e064151ac
2
Makefile
2
Makefile
@ -10,7 +10,7 @@ build: build/ros2aria/ros2aria
|
|||||||
|
|
||||||
# .uploaded: build/ros2aria/ros2aria
|
# .uploaded: build/ros2aria/ros2aria
|
||||||
upload:
|
upload:
|
||||||
rsync -r . lab1_5@pionier6:~/ros2aria
|
rsync -r . lab1_5@pionier5:~/ros2aria
|
||||||
touch .uploaded
|
touch .uploaded
|
||||||
|
|
||||||
# upload: .uploaded
|
# upload: .uploaded
|
||||||
|
@ -1,5 +1,9 @@
|
|||||||
version: "3"
|
# docker compose -f compose.ros2aria.yaml up
|
||||||
services:
|
services:
|
||||||
ros2aria:
|
ros2aria:
|
||||||
build: .
|
build: .
|
||||||
command: ros2 run ros2aria ros2aria --ros-args -p pioneer_id:=${PIONEER_ID}
|
network_mode: host
|
||||||
|
ipc: host
|
||||||
|
command: ros2 run ros2aria ros2aria --ros-args -p pioneer_id:=${PIONEER_ID}
|
||||||
|
devices:
|
||||||
|
- /dev/ttyS0
|
||||||
|
30
src/pioneer_description/CMakeLists.txt
Normal file
30
src/pioneer_description/CMakeLists.txt
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(pioneer_description)
|
||||||
|
|
||||||
|
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||||
|
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# find dependencies
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
# uncomment the following section in order to fill in
|
||||||
|
# further dependencies manually.
|
||||||
|
# find_package(<dependency> REQUIRED)
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
# the following line skips the linter which checks for copyrights
|
||||||
|
# comment the line when a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_copyright_FOUND TRUE)
|
||||||
|
# the following line skips cpplint (only works in a git repo)
|
||||||
|
# comment the line when this package is in a git repo and when
|
||||||
|
# a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_cpplint_FOUND TRUE)
|
||||||
|
ament_lint_auto_find_test_dependencies()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
install(DIRECTORY urdf launch
|
||||||
|
DESTINATION share/${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_package()
|
37
src/pioneer_description/launch/pioneer_description.launch.py
Normal file
37
src/pioneer_description/launch/pioneer_description.launch.py
Normal file
@ -0,0 +1,37 @@
|
|||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch.substitutions import Command, LaunchConfiguration, PythonExpression
|
||||||
|
from launch.conditions import IfCondition, UnlessCondition
|
||||||
|
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
|
||||||
|
import launch
|
||||||
|
from launch.substitutions import Command, LaunchConfiguration
|
||||||
|
import launch_ros
|
||||||
|
import os
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
|
||||||
|
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||||
|
from launch.conditions import IfCondition
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
pkg_share = launch_ros.substitutions.FindPackageShare(
|
||||||
|
package='pioneer_description').find('micromouse_description')
|
||||||
|
|
||||||
|
default_model_path = os.path.join(
|
||||||
|
pkg_share, 'urdf/pioneer3dx.urdf.xacro')
|
||||||
|
|
||||||
|
robot_state_publisher_node = launch_ros.actions.Node(
|
||||||
|
namespace='pioneer5',
|
||||||
|
package='robot_state_publisher',
|
||||||
|
executable='robot_state_publisher',
|
||||||
|
parameters=[{'robot_description': Command(
|
||||||
|
['xacro ', LaunchConfiguration('model')])}]
|
||||||
|
)
|
||||||
|
|
||||||
|
return launch.LaunchDescription([
|
||||||
|
launch.actions.DeclareLaunchArgument(name='model', default_value=default_model_path,
|
||||||
|
description='Absolute path to robot urdf file'),
|
||||||
|
robot_state_publisher_node,
|
||||||
|
])
|
18
src/pioneer_description/package.xml
Normal file
18
src/pioneer_description/package.xml
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>pioneer_description</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="jakub.delicat@husarion.com">deli</maintainer>
|
||||||
|
<license>TODO: License declaration</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
367
src/pioneer_description/urdf/pioneer3dx.urdf
Normal file
367
src/pioneer_description/urdf/pioneer3dx.urdf
Normal file
@ -0,0 +1,367 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<!-- =================================================================================== -->
|
||||||
|
<!-- | This document was autogenerated by xacro from pioneer3dx.urdf.xacro | -->
|
||||||
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||||
|
<!-- =================================================================================== -->
|
||||||
|
<robot name="pioneer3dx" 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">
|
||||||
|
<!--<include filename="$(find amr_robots_description)/urdf/materials.xacro"/>-->
|
||||||
|
<!-- Chassis -->
|
||||||
|
|
||||||
|
<link name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="3.5" />
|
||||||
|
<!--<origin xyz="-0.025 0 -0.223"/>-->
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
|
||||||
|
</inertial>
|
||||||
|
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="-0.045 0 0.148" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/chassis.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="ChassisRed">
|
||||||
|
<color rgba="0.851 0.0 0.0 1.0" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<box size="0.01 0.01 0.01" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<link name="top_plate">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.01" />
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/top.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="TopBlack">
|
||||||
|
<color rgba="0.038 0.038 0.038 1.0" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="top_plate">
|
||||||
|
<!-- material value="Gazebo/Black"/ -->
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
<joint name="base_top_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="-0.045 0 0.234" />
|
||||||
|
<axis xzy="0 0 1" />
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="top_plate" />
|
||||||
|
</joint>
|
||||||
|
<!-- <link name="front_sonar">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.0001"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/front_sonar.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="SonarYellow">
|
||||||
|
<color rgba="0.715 0.583 0.210 1.0"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link> -->
|
||||||
|
<!-- <gazebo reference="front_sonar">
|
||||||
|
<material value="Gazebo/Yellow"/>
|
||||||
|
</gazebo> -->
|
||||||
|
<!-- <joint name="base_front_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="-0.198 0 0.208"/>
|
||||||
|
<parent link="base_link"/>
|
||||||
|
<child link="front_sonar"/>
|
||||||
|
</joint> -->
|
||||||
|
<joint name="base_back_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="0.109 0 0.209" />
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="sonar_frame" />
|
||||||
|
</joint>
|
||||||
|
<link name="sonar_frame">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0" />
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/sonar_frame.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="SonarYellow">
|
||||||
|
<color rgba="0.715 0.583 0.210 1.0" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<!-- Caster -->
|
||||||
|
<joint name="base_caster_swivel_joint" type="continuous">
|
||||||
|
<origin rpy="0 0 0" xyz="-0.185 0 0.055" />
|
||||||
|
<anchor xyz="0 0 0" />
|
||||||
|
<limit effort="100" k_velocity="0" velocity="100" />
|
||||||
|
<joint_properties damping="0.0" friction="0.0" />
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="caster_swivel" />
|
||||||
|
</joint>
|
||||||
|
<link name="caster_swivel">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.1" />
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_swivel.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="caster_swivel">
|
||||||
|
<color rgba="0.5 0.5 0.5 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="caster_swivel">
|
||||||
|
<material value="Gazebo/Grey" />
|
||||||
|
</gazebo>
|
||||||
|
<!-- Center Wheel + Hubcap -->
|
||||||
|
<link name="caster_hubcap">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.01" />
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_hubcap.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="caster_swivel">
|
||||||
|
<color rgba="0.5 0.5 0.5 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<box size="0.05 0.05 0.05" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="caster_hubcap">
|
||||||
|
<material value="Gazebo/Grey" />
|
||||||
|
</gazebo>
|
||||||
|
<joint name="caster_swivel_hubcap_joint" type="continuous">
|
||||||
|
<origin rpy="0 0 0" xyz="-0.026 0 -0.016" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
<anchor xyz="0 0 0" />
|
||||||
|
<limit effort="100" k_velocity="0" velocity="100" />
|
||||||
|
<joint_properties damping="0.0" friction="0.0" />
|
||||||
|
<parent link="caster_swivel" />
|
||||||
|
<child link="caster_wheel" />
|
||||||
|
</joint>
|
||||||
|
<link name="caster_wheel">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.1" />
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry name="pioneer_geom">
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_wheel.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="WheelBlack">
|
||||||
|
<color rgba="0.117 0.117 0.117 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="-1.57079635 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<!--<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_wheel.stl"/>-->
|
||||||
|
<cylinder length="0.01" radius="0.0375" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="left_hub">
|
||||||
|
<material value="Gazebo/Yellow" />
|
||||||
|
</gazebo>
|
||||||
|
<joint name="caster_wheel_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="-0.0035 0 -0.001" />
|
||||||
|
<parent link="caster_wheel" />
|
||||||
|
<child link="caster_hubcap" />
|
||||||
|
</joint>
|
||||||
|
<link name="left_hub">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/left_hubcap.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="HubcapYellow">
|
||||||
|
<color rgba="1.0 0.811 0.151 1.0" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="-1.57079635 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<!--<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_wheel.stl"/>-->
|
||||||
|
<cylinder length="0.01" radius="0.09" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hub_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="0 0.15 0.08" />
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="left_hub" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
</joint>
|
||||||
|
<link name="left_wheel">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/left_wheel.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="WheelBlack">
|
||||||
|
<color rgba="0.117 0.117 0.117 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<joint name="left_wheel_joint" type="fixed">
|
||||||
|
<!-- type="continuous" -->
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<parent link="left_hub" />
|
||||||
|
<child link="left_wheel" />
|
||||||
|
</joint>
|
||||||
|
<gazebo reference="left_wheel_joint">
|
||||||
|
<material value="Gazebo/Black" />
|
||||||
|
</gazebo>
|
||||||
|
<link name="right_hub">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/right_hubcap.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="HubcapYellow">
|
||||||
|
<color rgba="1.0 0.811 0.151 1.0" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="-1.57079635 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<!--<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/caster_wheel.stl"/>-->
|
||||||
|
<cylinder length="0.01" radius="0.09" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="right_hub">
|
||||||
|
<material value="Gazebo/Yellow" />
|
||||||
|
</gazebo>
|
||||||
|
<joint name="right_hub_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="0 -0.15 0.08" />
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="right_hub" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
</joint>
|
||||||
|
<link name="right_wheel">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/right_wheel.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="WheelBlack">
|
||||||
|
<color rgba="0.117 0.117 0.117 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<joint name="right_wheel_joint" type="fixed">
|
||||||
|
<!-- type="continuous" -->
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
|
<parent link="right_hub" />
|
||||||
|
<child link="right_wheel" />
|
||||||
|
</joint>
|
||||||
|
<gazebo reference="right_wheel_joint">
|
||||||
|
<material value="Gazebo/Black" />
|
||||||
|
</gazebo>
|
||||||
|
<create>
|
||||||
|
<sonar_frame parent="base_link" />
|
||||||
|
<top_plate parent="base_link" />
|
||||||
|
</create>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="laser">
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<box size="0.1 0.1 0.1" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://amr_robots_description/meshes/p3dx_meshes/hokuyo_convex.stl" />
|
||||||
|
</geometry>
|
||||||
|
<material name="Hokuyo">
|
||||||
|
<color rgba="0 0 0 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<inertial>
|
||||||
|
<mass value="1e-5" />
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
<joint name="hokuyo_joint" type="fixed">
|
||||||
|
<axis xyz="0 0 0" />
|
||||||
|
<origin xyz="0.040 0 0.0625" rpy="0 0 0" />
|
||||||
|
<parent link="sonar_frame" />
|
||||||
|
<child link="laser" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="camera_frame">
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<box size="0.095 0.03 0.03" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
<joint name="camera_joint" type="fixed">
|
||||||
|
<axis xyz="0 0 0" />
|
||||||
|
<origin xyz="0.040 0 0.1125" rpy="0 0 0" />
|
||||||
|
<parent link="sonar_frame" />
|
||||||
|
<child link="camera_frame" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- ====================[Gripper]====================== -->
|
||||||
|
|
||||||
|
<!-- <link name="gripper_base">
|
||||||
|
</link> -->
|
||||||
|
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
|
||||||
|
<alwaysOn>true</alwaysOn>
|
||||||
|
<updateRate>100</updateRate>
|
||||||
|
<leftJoint>left_wheel_joint</leftJoint>
|
||||||
|
<rightJoint>right_wheel_joint</rightJoint>
|
||||||
|
<wheelSeparation>0.158</wheelSeparation>
|
||||||
|
<wheelDiameter>0.12</wheelDiameter>
|
||||||
|
<torque>5</torque>
|
||||||
|
<!-- interface:position name="position_iface_0"/ -->
|
||||||
|
<commandTopic>cmd_vel</commandTopic>
|
||||||
|
<robotBaseFrame>base_link</robotBaseFrame>
|
||||||
|
<odometryTopic>odom</odometryTopic>
|
||||||
|
<odometryFrame>odom</odometryFrame>
|
||||||
|
</plugin>
|
||||||
|
<!-- TODO include P3D (ground truth) plugin -->
|
||||||
|
<!-- XXX old urdf included a gazebo_ros_controller_manager plugin with a 1 second update rate -->
|
||||||
|
</gazebo>
|
||||||
|
</robot>
|
@ -18,7 +18,7 @@ Ros2Aria::Ros2Aria()
|
|||||||
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
|
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
|
||||||
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
|
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
|
||||||
|
|
||||||
pose_pub_ = this->create_publisher<nav_msgs::msg::Odometry>("pose", 1000);
|
pose_pub_ = this->create_publisher<nav_msgs::msg::Odometry>("odom/wheels", 1000);
|
||||||
|
|
||||||
wheels_pub_ = this->create_publisher<sensor_msgs::msg::JointState>("wheels", 1000);
|
wheels_pub_ = this->create_publisher<sensor_msgs::msg::JointState>("wheels", 1000);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user