added files
This commit is contained in:
parent
714720c0d0
commit
80afe23cb2
22
.vscode/c_cpp_properties.json
vendored
Normal file
22
.vscode/c_cpp_properties.json
vendored
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
{
|
||||||
|
"configurations": [
|
||||||
|
{
|
||||||
|
"browse": {
|
||||||
|
"databaseFilename": "${default}",
|
||||||
|
"limitSymbolsToIncludedHeaders": false
|
||||||
|
},
|
||||||
|
"includePath": [
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/my_robot_interfaces/include/**",
|
||||||
|
"/opt/ros/humble/include/**",
|
||||||
|
"/home/ros-laptop1/Desktop/ros2_ws/src/my_robot1_description/include/**",
|
||||||
|
"/usr/include/**"
|
||||||
|
],
|
||||||
|
"name": "ROS",
|
||||||
|
"intelliSenseMode": "gcc-x64",
|
||||||
|
"compilerPath": "/usr/bin/gcc",
|
||||||
|
"cStandard": "gnu11",
|
||||||
|
"cppStandard": "c++14"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"version": 4
|
||||||
|
}
|
16
.vscode/settings.json
vendored
Normal file
16
.vscode/settings.json
vendored
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
{
|
||||||
|
"python.autoComplete.extraPaths": [
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/turtlesim_catch_them_all/lib/python3.10/site-packages",
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/my_py_pkg/lib/python3.10/site-packages",
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/my_robot_interfaces/local/lib/python3.10/dist-packages",
|
||||||
|
"/opt/ros/humble/lib/python3.10/site-packages",
|
||||||
|
"/opt/ros/humble/local/lib/python3.10/dist-packages"
|
||||||
|
],
|
||||||
|
"python.analysis.extraPaths": [
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/turtlesim_catch_them_all/lib/python3.10/site-packages",
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/my_py_pkg/lib/python3.10/site-packages",
|
||||||
|
"/home/ros-laptop1/Desktop/turtlebotrhodes_ws/install/my_robot_interfaces/local/lib/python3.10/dist-packages",
|
||||||
|
"/opt/ros/humble/lib/python3.10/site-packages",
|
||||||
|
"/opt/ros/humble/local/lib/python3.10/dist-packages"
|
||||||
|
]
|
||||||
|
}
|
2
README.md
Normal file
2
README.md
Normal file
@ -0,0 +1,2 @@
|
|||||||
|
# Udemy Course 2
|
||||||
|
This is my code and scripts from the udemy course I took [here](https://www.udemy.com/course/ros2-tf-urdf-rviz-gazebo). I was an amazing course and I would highly recommend it for getting an basic introduction to ROS 2.
|
16
my_robot1_bringup/CMakeLists.txt
Normal file
16
my_robot1_bringup/CMakeLists.txt
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(my_robot1_bringup)
|
||||||
|
|
||||||
|
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)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY launch rviz worlds
|
||||||
|
DESTINATION share/${PROJECT_NAME}/
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_package()
|
17
my_robot1_bringup/launch/my_robot1_gazebo.launch.xml
Normal file
17
my_robot1_bringup/launch/my_robot1_gazebo.launch.xml
Normal file
@ -0,0 +1,17 @@
|
|||||||
|
<launch>
|
||||||
|
<let name="urdf_path" value="$(find-pkg-share my_robot1_description)/urdf/my_robot1.urdf.xacro"/>
|
||||||
|
<let name="rviz_config_path" value="$(find-pkg-share my_robot1_bringup)/rviz/urdf_config.rviz"/>
|
||||||
|
|
||||||
|
<node pkg="robot_state_publisher" exec="robot_state_publisher">
|
||||||
|
<param name="robot_description" value="$(command 'xacro $(var urdf_path)')"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
|
||||||
|
<arg name="world" value="$(find-pkg-share my_robot1_bringup)/worlds/test_world.world.xml"/>
|
||||||
|
</include>
|
||||||
|
|
||||||
|
<node pkg="gazebo_ros" exec="spawn_entity.py" args="-topic robot_description -entity my_robot1"/>
|
||||||
|
|
||||||
|
<node pkg="rviz2" exec="rviz2" output="screen" args="-d $(var rviz_config_path)" />
|
||||||
|
|
||||||
|
</launch>
|
24
my_robot1_bringup/package.xml
Normal file
24
my_robot1_bringup/package.xml
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
<?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>my_robot1_bringup</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="coolemail45@proton.me">ros-laptop1</maintainer>
|
||||||
|
<license>TODO: License declaration</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<exec_depend>my_robot1_description</exec_depend>
|
||||||
|
<exec_depend>robot_state_publisher</exec_depend>
|
||||||
|
<exec_depend>gazebo_ros</exec_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
250
my_robot1_bringup/rviz/urdf_config.rviz
Normal file
250
my_robot1_bringup/rviz/urdf_config.rviz
Normal file
@ -0,0 +1,250 @@
|
|||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 0
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
- /RobotModel1
|
||||||
|
- /Camera1
|
||||||
|
- /Camera1/Visibility1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 176
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
- Class: rviz_common/Time
|
||||||
|
Experimental: false
|
||||||
|
Name: Time
|
||||||
|
SyncMode: 0
|
||||||
|
SyncSource: ""
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Class: rviz_default_plugins/TF
|
||||||
|
Enabled: true
|
||||||
|
Frame Timeout: 15
|
||||||
|
Frames:
|
||||||
|
All Enabled: true
|
||||||
|
base_footprint:
|
||||||
|
Value: true
|
||||||
|
base_link:
|
||||||
|
Value: true
|
||||||
|
camera_link:
|
||||||
|
Value: true
|
||||||
|
caster_wheel_link:
|
||||||
|
Value: true
|
||||||
|
left_wheel_link:
|
||||||
|
Value: true
|
||||||
|
odom:
|
||||||
|
Value: true
|
||||||
|
right_wheel_link:
|
||||||
|
Value: true
|
||||||
|
Marker Scale: 1
|
||||||
|
Name: TF
|
||||||
|
Show Arrows: true
|
||||||
|
Show Axes: true
|
||||||
|
Show Names: false
|
||||||
|
Tree:
|
||||||
|
odom:
|
||||||
|
base_footprint:
|
||||||
|
base_link:
|
||||||
|
camera_link:
|
||||||
|
{}
|
||||||
|
caster_wheel_link:
|
||||||
|
{}
|
||||||
|
left_wheel_link:
|
||||||
|
{}
|
||||||
|
right_wheel_link:
|
||||||
|
{}
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
- Alpha: 1
|
||||||
|
Class: rviz_default_plugins/RobotModel
|
||||||
|
Collision Enabled: false
|
||||||
|
Description File: ""
|
||||||
|
Description Source: Topic
|
||||||
|
Description Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /robot_description
|
||||||
|
Enabled: true
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base_footprint:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
base_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
caster_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
left_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
right_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Mass Properties:
|
||||||
|
Inertia: false
|
||||||
|
Mass: false
|
||||||
|
Name: RobotModel
|
||||||
|
TF Prefix: ""
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Visual Enabled: true
|
||||||
|
- Class: rviz_default_plugins/Camera
|
||||||
|
Enabled: true
|
||||||
|
Far Plane Distance: 100
|
||||||
|
Image Rendering: background and overlay
|
||||||
|
Name: Camera
|
||||||
|
Overlay Alpha: 0
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /camera_sensor/image_raw
|
||||||
|
Value: true
|
||||||
|
Visibility:
|
||||||
|
Grid: false
|
||||||
|
RobotModel: false
|
||||||
|
TF: false
|
||||||
|
Value: true
|
||||||
|
Zoom Factor: 1
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base_footprint
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Covariance x: 0.25
|
||||||
|
Covariance y: 0.25
|
||||||
|
Covariance yaw: 0.06853891909122467
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/Orbit
|
||||||
|
Distance: 1.442779302597046
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Focal Shape Fixed Size: true
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name: Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: 0.4553983211517334
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: Orbit (rviz)
|
||||||
|
Yaw: 0.16539859771728516
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Camera:
|
||||||
|
collapsed: false
|
||||||
|
Displays:
|
||||||
|
collapsed: false
|
||||||
|
Height: 1001
|
||||||
|
Hide Left Dock: false
|
||||||
|
Hide Right Dock: false
|
||||||
|
QMainWindow State: 000000ff00000000fd0000000400000000000002cb00000323fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000007901000003fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004e000000ff000000ff01000003fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061010000014e000002230000002e01000003000000010000011000000323fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004e00000323000000d701000003fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000004efc0100000002fb0000000800540069006d0065010000000000000780000002e701000003fb0000000800540069006d00650100000000000004500000000000000000000003a30000032300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Time:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: false
|
||||||
|
Width: 1920
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
2079
my_robot1_bringup/worlds/test_world.world.xml
Normal file
2079
my_robot1_bringup/worlds/test_world.world.xml
Normal file
File diff suppressed because it is too large
Load Diff
16
my_robot1_description/CMakeLists.txt
Normal file
16
my_robot1_description/CMakeLists.txt
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(my_robot1_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)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY urdf launch rviz
|
||||||
|
DESTINATION share/${PROJECT_NAME}/
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_package()
|
42
my_robot1_description/launch/display.launch.py
Normal file
42
my_robot1_description/launch/display.launch.py
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
import os
|
||||||
|
from ament_index_python import get_package_share_directory
|
||||||
|
from launch_ros.parameter_descriptions import ParameterValue
|
||||||
|
from launch.substitutions import Command
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
|
||||||
|
urdf_path = os.path.join(get_package_share_directory('my_robot1_description'), 'urdf', 'my_robot1.urdf.xacro')
|
||||||
|
robot_description = ParameterValue(Command(['xacro ', urdf_path]), value_type=str)
|
||||||
|
|
||||||
|
rviz_config_path = os.path.join(get_package_share_directory('my_robot1_description'), 'rviz', 'urdf_config.rviz')
|
||||||
|
|
||||||
|
robot_state_publisher_node = Node(
|
||||||
|
package="robot_state_publisher",
|
||||||
|
executable="robot_state_publisher",
|
||||||
|
parameters = [{"robot_description": robot_description}]
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
joint_state_publisher_gui_node = Node(
|
||||||
|
package="joint_state_publisher_gui",
|
||||||
|
executable="joint_state_publisher_gui",
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
rviz2_node = Node(
|
||||||
|
package="rviz2",
|
||||||
|
executable="rviz2",
|
||||||
|
arguments=['-d', rviz_config_path]
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
robot_state_publisher_node,
|
||||||
|
joint_state_publisher_gui_node,
|
||||||
|
rviz2_node
|
||||||
|
])
|
12
my_robot1_description/launch/display.launch.xml
Normal file
12
my_robot1_description/launch/display.launch.xml
Normal file
@ -0,0 +1,12 @@
|
|||||||
|
<launch>
|
||||||
|
<let name="urdf_path" value="$(find-pkg-share my_robot1_description)/urdf/my_robot1.urdf.xacro"/>
|
||||||
|
<let name="rviz_config_path" value="$(find-pkg-share my_robot1_description)/rviz/urdf_config.rviz"/>
|
||||||
|
|
||||||
|
<node pkg="robot_state_publisher" exec="robot_state_publisher">
|
||||||
|
<param name="robot_description" value="$(command 'xacro $(var urdf_path)')"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node pkg="joint_state_publisher_gui" exec="joint_state_publisher_gui" />
|
||||||
|
|
||||||
|
<node pkg="rviz2" exec="rviz2" output="screen" args="-d $(var rviz_config_path)" />
|
||||||
|
</launch>
|
18
my_robot1_description/package.xml
Normal file
18
my_robot1_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>my_robot1_description</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="coolemail45@proton.me">ros-laptop1</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>
|
215
my_robot1_description/rviz/urdf_config.rviz
Normal file
215
my_robot1_description/rviz/urdf_config.rviz
Normal file
@ -0,0 +1,215 @@
|
|||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 87
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
- /RobotModel1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 637
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
- Class: rviz_common/Time
|
||||||
|
Experimental: false
|
||||||
|
Name: Time
|
||||||
|
SyncMode: 0
|
||||||
|
SyncSource: ""
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Class: rviz_default_plugins/TF
|
||||||
|
Enabled: true
|
||||||
|
Frame Timeout: 15
|
||||||
|
Frames:
|
||||||
|
All Enabled: true
|
||||||
|
base_footprint:
|
||||||
|
Value: true
|
||||||
|
base_link:
|
||||||
|
Value: true
|
||||||
|
caster_wheel_link:
|
||||||
|
Value: true
|
||||||
|
left_wheel_link:
|
||||||
|
Value: true
|
||||||
|
right_wheel_link:
|
||||||
|
Value: true
|
||||||
|
Marker Scale: 1
|
||||||
|
Name: TF
|
||||||
|
Show Arrows: true
|
||||||
|
Show Axes: true
|
||||||
|
Show Names: false
|
||||||
|
Tree:
|
||||||
|
base_footprint:
|
||||||
|
base_link:
|
||||||
|
caster_wheel_link:
|
||||||
|
{}
|
||||||
|
left_wheel_link:
|
||||||
|
{}
|
||||||
|
right_wheel_link:
|
||||||
|
{}
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
- Alpha: 1
|
||||||
|
Class: rviz_default_plugins/RobotModel
|
||||||
|
Collision Enabled: false
|
||||||
|
Description File: ""
|
||||||
|
Description Source: Topic
|
||||||
|
Description Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /robot_description
|
||||||
|
Enabled: true
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base_footprint:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
base_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
caster_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
left_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
right_wheel_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Mass Properties:
|
||||||
|
Inertia: false
|
||||||
|
Mass: false
|
||||||
|
Name: RobotModel
|
||||||
|
TF Prefix: ""
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Visual Enabled: true
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base_footprint
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Covariance x: 0.25
|
||||||
|
Covariance y: 0.25
|
||||||
|
Covariance yaw: 0.06853891909122467
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/Orbit
|
||||||
|
Distance: 2.7850098609924316
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Focal Shape Fixed Size: true
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name: Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: -0.014601386152207851
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: Orbit (rviz)
|
||||||
|
Yaw: 1.6503971815109253
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Displays:
|
||||||
|
collapsed: false
|
||||||
|
Height: 1001
|
||||||
|
Hide Left Dock: false
|
||||||
|
Hide Right Dock: false
|
||||||
|
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000323fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000007901000003fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004e00000323000000ff01000003fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000011000000323fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004e00000323000000d701000003fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000004efc0100000002fb0000000800540069006d0065010000000000000780000002e701000003fb0000000800540069006d00650100000000000004500000000000000000000005040000032300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Time:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: false
|
||||||
|
Width: 1920
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
48
my_robot1_description/urdf/camera.xacro
Normal file
48
my_robot1_description/urdf/camera.xacro
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="camera_length" value="0.01"/>
|
||||||
|
<xacro:property name="camera_width" value="0.1"/>
|
||||||
|
<xacro:property name="camera_height" value="0.05"/>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="camera_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${camera_length} ${camera_width} ${camera_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<material name="gray" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${camera_length} ${camera_width} ${camera_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="0.1" l="${camera_length}" w="${camera_width}" h="${camera_height}" xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="base_camera_joint" type="fixed">
|
||||||
|
<parent link="base_link"/>
|
||||||
|
<child link="camera_link"/>
|
||||||
|
<origin xyz="${(base_length + camera_length)/ 2} 0 ${base_height/2}" rpy="0 0 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<gazebo reference="camera_link">
|
||||||
|
<material>Gazebo/Red</material>
|
||||||
|
<sensor name="camera_sensor" type="camera">
|
||||||
|
<!-- x y z r p y-->
|
||||||
|
<pose>0 0 0 0 0 0</pose>
|
||||||
|
<!-- whether you can see projection in gazebo or not-->
|
||||||
|
<visualize>true</visualize>
|
||||||
|
<!-- update rate in hz-->
|
||||||
|
<update_rate>10.0</update_rate>
|
||||||
|
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||||
|
<!-- camera link -->
|
||||||
|
<frame_name>camera_link</frame_name>
|
||||||
|
</plugin>
|
||||||
|
</sensor>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
49
my_robot1_description/urdf/common_properties.xacro
Normal file
49
my_robot1_description/urdf/common_properties.xacro
Normal file
@ -0,0 +1,49 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<material name="blue">
|
||||||
|
<color rgba="0 0 0.5 1"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="gray">
|
||||||
|
<color rgba="0.5 0.5 0.5 1.0"/>
|
||||||
|
</material>
|
||||||
|
<material name="orange">
|
||||||
|
<color rgba="0.95 0.647 0.388 1"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="yellow">
|
||||||
|
<color rgba="0.95 1 0.388 1" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<xacro:macro name="box_inertia" params="m l w h xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<mass value="${m}"/>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
|
<inertia ixx="${(m/12) * (h*h + l*l)}" ixy="0" ixz="0"
|
||||||
|
iyy="${(m/12) * (w*w + l*l)}" iyz="0"
|
||||||
|
izz="${(m/12) * (w*w + h*h)}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
<xacro:macro name="cylinder_inertia" params="m r h xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<mass value="${m}"/>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
|
<inertia ixx="${(m/12) * (3*r*r + h*h)}" ixy="0" ixz="0"
|
||||||
|
iyy="${(m/12) * (3*r*r + h*h)}" iyz="0"
|
||||||
|
izz="${(2/m) * (r*r)}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
<xacro:macro name="sphere_inertia" params="m r xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<mass value="${m}"/>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
|
<inertia ixx="${(2/5) * m * r * r}" ixy="0" ixz="0"
|
||||||
|
iyy="${(2/5) * m * r * r}" iyz="0"
|
||||||
|
izz="${(2/5) * m * r * r}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
</robot>
|
107
my_robot1_description/urdf/mobile_base.xacro
Normal file
107
my_robot1_description/urdf/mobile_base.xacro
Normal file
@ -0,0 +1,107 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="base_length" value="0.6"/>
|
||||||
|
<xacro:property name="base_width" value="0.4"/>
|
||||||
|
<xacro:property name="base_height" value="0.2"/>
|
||||||
|
<xacro:property name="wheel_radius" value="0.1"/>
|
||||||
|
<xacro:property name="wheel_length" value="0.05"/>
|
||||||
|
|
||||||
|
|
||||||
|
<xacro:macro name="wheel_macro" params="prefix">
|
||||||
|
<link name="${prefix}_wheel_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="${pi / 2.0} 0 0"/>
|
||||||
|
<material name="gray"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="${pi / 2.0} 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="1.0" r="${2*wheel_radius}" h="${2*wheel_length}"
|
||||||
|
xyz="0 0 0" rpy="${pi / 2.0} 0 0"/>
|
||||||
|
</link>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="base_footprint">
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="base_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${base_length} ${base_width} ${base_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${base_height/2.0}" rpy="0 0 0"/>
|
||||||
|
<material name="blue"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${base_length} ${base_width} ${base_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${base_height/2.0}" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="5.0" l="${2*base_length}" w="${2*base_width}" h="${2*base_height}"
|
||||||
|
xyz="0 0 ${base_height/2.0}" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<xacro:wheel_macro prefix="right" />
|
||||||
|
<xacro:wheel_macro prefix="left" />
|
||||||
|
|
||||||
|
<link name="caster_wheel_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${wheel_radius / 2.0}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<material name="gray"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${wheel_radius / 2.0}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:sphere_inertia m="0.5" r="${2*wheel_radius / 2.0}"
|
||||||
|
xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="base_joint" type="fixed">
|
||||||
|
<parent link="base_footprint" />
|
||||||
|
<child link="base_link" />
|
||||||
|
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_left_wheel_joint" type="continuous">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="left_wheel_link" />
|
||||||
|
<origin xyz="${base_length / -4.0} ${base_width/2 + wheel_length/2} 0" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_right_wheel_joint" type="continuous">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="right_wheel_link" />
|
||||||
|
<origin xyz="${base_length / -4.0} -${base_width/2 + wheel_length/2} 0" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_caster_wheel_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="caster_wheel_link" />
|
||||||
|
<origin xyz="${base_length / 3.0} 0 -${wheel_radius / 2}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Mount Arm -->
|
||||||
|
<joint name="base_arm_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="arm_base_link" />
|
||||||
|
<origin xyz="${(arm_base_width / -2) + (base_length / 2.0)} 0 ${base_height + (arm_base_height / 2)}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
</robot>
|
73
my_robot1_description/urdf/mobile_base_gazebo.xacro
Normal file
73
my_robot1_description/urdf/mobile_base_gazebo.xacro
Normal file
@ -0,0 +1,73 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<material>Gazebo/Blue</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="right_wheel_link">
|
||||||
|
<material>Gazebo/Gray</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="left_wheel_link">
|
||||||
|
<material>Gazebo/Gray</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="caster_wheel_link">
|
||||||
|
<material>Gazebo/Gray</material>
|
||||||
|
<mu1 value="0.1" />
|
||||||
|
<mu2 value="0.1" />
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
||||||
|
<!-- Update rate in Hz -->
|
||||||
|
<update_rate>50</update_rate>
|
||||||
|
<!-- Wheels -->
|
||||||
|
<left_joint>base_left_wheel_joint</left_joint>
|
||||||
|
<right_joint>base_right_wheel_joint</right_joint>
|
||||||
|
<!-- Size -->
|
||||||
|
<wheel_separation>${wheel_length + base_width}</wheel_separation>
|
||||||
|
<wheel_diameter>${wheel_radius}</wheel_diameter>
|
||||||
|
|
||||||
|
<!-- Ros Topic -->
|
||||||
|
<command_topic>cmd_vel</command_topic>
|
||||||
|
<!-- output -->
|
||||||
|
<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>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- Arm -->
|
||||||
|
<gazebo reference="arm_base_link">
|
||||||
|
<material>Gazebo/Orange</material>
|
||||||
|
</gazebo>
|
||||||
|
<gazebo reference="forearm_link">
|
||||||
|
<material>Gazebo/Yellow</material>
|
||||||
|
</gazebo>
|
||||||
|
<gazebo reference="hand_link">
|
||||||
|
<material>Gazebo/Orange</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
|
||||||
|
<!-- Update rate in Hertz -->
|
||||||
|
<update_rate>10</update_rate>
|
||||||
|
|
||||||
|
<!-- Name of joints in the model whose states will be published. -->
|
||||||
|
<joint_name>arm_base_forearm_joint</joint_name>
|
||||||
|
<joint_name>forearm_hand_joint</joint_name>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="joint_pose_trajectory" filename="libgazebo_ros_joint_pose_trajectory.so">
|
||||||
|
<update_rate>2</update_rate>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
10
my_robot1_description/urdf/my_robot1.urdf.xacro
Normal file
10
my_robot1_description/urdf/my_robot1.urdf.xacro
Normal file
@ -0,0 +1,10 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="my_robot1" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:include filename="common_properties.xacro" />
|
||||||
|
<xacro:include filename="robot_arm.xacro" />
|
||||||
|
<xacro:include filename="mobile_base.xacro" />
|
||||||
|
<xacro:include filename="camera.xacro" />
|
||||||
|
<xacro:include filename="mobile_base_gazebo.xacro" />
|
||||||
|
|
||||||
|
</robot>
|
85
my_robot1_description/urdf/robot_arm.xacro
Normal file
85
my_robot1_description/urdf/robot_arm.xacro
Normal file
@ -0,0 +1,85 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="arm_base_length" value="0.1"/>
|
||||||
|
<xacro:property name="arm_base_width" value="0.1"/>
|
||||||
|
<xacro:property name="arm_base_height" value="0.02"/>
|
||||||
|
|
||||||
|
<xacro:property name="arm_radius" value="0.02"/>
|
||||||
|
<xacro:property name="arm_forearm_length" value="0.3"/>
|
||||||
|
<xacro:property name="arm_hand_length" value="0.3"/>
|
||||||
|
|
||||||
|
<link name="arm_base_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<material name="orange"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="0.5" l="${arm_base_length}" w="${arm_base_width}" h="${arm_base_height}"
|
||||||
|
xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="forearm_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${arm_radius}" length="${arm_forearm_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
||||||
|
<material name="yellow"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${arm_radius}" length="${arm_forearm_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="0.3" r="${arm_radius}" h="${arm_forearm_length}"
|
||||||
|
xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="hand_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${arm_radius}" length="${arm_hand_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
||||||
|
<material name="orange"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${arm_radius}" length="${arm_hand_length}"/>
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="0.3" r="${arm_radius}" h="${arm_hand_length}"
|
||||||
|
xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="arm_base_forearm_joint" type="revolute">
|
||||||
|
<parent link="arm_base_link" />
|
||||||
|
<child link="forearm_link" />
|
||||||
|
<origin xyz="0 0 ${arm_base_height/2}" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="0" upper="${pi/2}" velocity="100" effort="100" />
|
||||||
|
<dynamics friction="0.05" damping="0.1" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="forearm_hand_joint" type="revolute">
|
||||||
|
<parent link="forearm_link" />
|
||||||
|
<child link="hand_link" />
|
||||||
|
<origin xyz="0 0 ${arm_hand_length}" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="0" upper="${pi/2}" velocity="100" effort="100" />
|
||||||
|
<dynamics friction="0.05" damping="0.1" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
</robot>
|
84
my_robot1_description/urdf_his/arm.xacro
Normal file
84
my_robot1_description/urdf_his/arm.xacro
Normal file
@ -0,0 +1,84 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="arm_base_length" value="0.1" />
|
||||||
|
<xacro:property name="arm_base_width" value="0.1" />
|
||||||
|
<xacro:property name="arm_base_height" value="0.02" />
|
||||||
|
<xacro:property name="forearm_radius" value="0.02" />
|
||||||
|
<xacro:property name="forearm_length" value="0.3" />
|
||||||
|
<xacro:property name="hand_radius" value="0.02" />
|
||||||
|
<xacro:property name="hand_length" value="0.3" />
|
||||||
|
|
||||||
|
<link name="arm_base_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
<material name="orange" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${arm_base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="0.5" l="${2*arm_base_length}" w="${2*arm_base_width}" h="${2*arm_base_height}"
|
||||||
|
xyz="0 0 ${arm_base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="forearm_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${forearm_radius}" length="${forearm_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${forearm_length / 2.0}" rpy="0 0 0" />
|
||||||
|
<material name="yellow" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${forearm_radius}" length="${forearm_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${forearm_length / 2.0}" rpy="0 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="0.3" r="${2*forearm_radius}" h="${2*forearm_length}"
|
||||||
|
xyz="0 0 ${forearm_length / 2.0}" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="hand_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${hand_radius}" length="${hand_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${hand_length / 2.0}" rpy="0 0 0" />
|
||||||
|
<material name="orange" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${hand_radius}" length="${hand_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${hand_length / 2.0}" rpy="0 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="0.3" r="${2*hand_radius}" h="${2*hand_length}"
|
||||||
|
xyz="0 0 ${hand_length / 2.0}" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="arm_base_forearm_joint" type="revolute">
|
||||||
|
<parent link="arm_base_link" />
|
||||||
|
<child link="forearm_link" />
|
||||||
|
<origin xyz="0 0 ${arm_base_height}" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
<limit lower="0" upper="${pi/2}" effort="100" velocity="100" />
|
||||||
|
<dynamics friction="0.05" damping="0.1" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="forearm_hand_joint" type="revolute">
|
||||||
|
<parent link="forearm_link" />
|
||||||
|
<child link="hand_link" />
|
||||||
|
<origin xyz="0 0 ${forearm_length}" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
<limit lower="0" upper="${pi/2}" effort="100" velocity="100" />
|
||||||
|
<dynamics friction="0.05" damping="0.1" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
</robot>
|
35
my_robot1_description/urdf_his/arm_gazebo.xacro
Normal file
35
my_robot1_description/urdf_his/arm_gazebo.xacro
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<gazebo reference="arm_base_link">
|
||||||
|
<material>Gazebo/Orange</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="forearm_link">
|
||||||
|
<material>Gazebo/Yellow</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="hand_link">
|
||||||
|
<material>Gazebo/Orange</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="joint_state_publisher_controller"
|
||||||
|
filename="libgazebo_ros_joint_state_publisher.so">
|
||||||
|
<!-- Update rate in Hertz -->
|
||||||
|
<update_rate>10</update_rate>
|
||||||
|
<!-- Name of joints in the model whose states will be published. -->
|
||||||
|
<joint_name>arm_base_forearm_joint</joint_name>
|
||||||
|
<joint_name>forearm_hand_joint</joint_name>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="joint_pose_trajectory_controller"
|
||||||
|
filename="libgazebo_ros_joint_pose_trajectory.so">
|
||||||
|
<!-- Update rate in Hz -->
|
||||||
|
<update_rate>2</update_rate>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
54
my_robot1_description/urdf_his/camera.xacro
Normal file
54
my_robot1_description/urdf_his/camera.xacro
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="camera_length" value="0.01" />
|
||||||
|
<xacro:property name="camera_width" value="0.1" />
|
||||||
|
<xacro:property name="camera_height" value="0.05" />
|
||||||
|
|
||||||
|
<link name="camera_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${camera_length} ${camera_width} ${camera_height}" />
|
||||||
|
</geometry>
|
||||||
|
<material name="grey" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${camera_length} ${camera_width} ${camera_height}" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="0.1" l="${camera_length}" w="${camera_width}" h="${camera_height}"
|
||||||
|
xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="base_camera_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="camera_link" />
|
||||||
|
<origin xyz="${(base_length + camera_length) / 2.0} 0 ${base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="camera_link_optical">
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="camera_optical_joint" type="fixed">
|
||||||
|
<!-- these values have to be these values otherwise the gazebo camera
|
||||||
|
image won't be aligned properly with the frame it is supposedly
|
||||||
|
originating from -->
|
||||||
|
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
||||||
|
<parent link="camera_link"/>
|
||||||
|
<child link="camera_link_optical"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<gazebo reference="camera_link">
|
||||||
|
<material>Gazebo/Red</material>
|
||||||
|
<sensor name="camera_sensor" type="camera">
|
||||||
|
<pose>0 0 0 0 0 0</pose>
|
||||||
|
<visualize>true</visualize>
|
||||||
|
<update_rate>10.0</update_rate>
|
||||||
|
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||||
|
<frame_name>camera_link_optical</frame_name>
|
||||||
|
</plugin>
|
||||||
|
</sensor>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
50
my_robot1_description/urdf_his/common_properties.xacro
Normal file
50
my_robot1_description/urdf_his/common_properties.xacro
Normal file
@ -0,0 +1,50 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<material name="blue">
|
||||||
|
<color rgba="0 0 0.5 1" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="grey">
|
||||||
|
<color rgba="0.5 0.5 0.5 1" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="orange">
|
||||||
|
<color rgba="1.0 0.5 0 1" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="yellow">
|
||||||
|
<color rgba="1.0 1.0 0 1" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<xacro:macro name="box_inertia" params="m l w h xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}" />
|
||||||
|
<mass value="${m}" />
|
||||||
|
<inertia ixx="${(m/12) * (h*h + l*l)}" ixy="0" ixz="0"
|
||||||
|
iyy="${(m/12) * (w*w + l*l)}" iyz="0"
|
||||||
|
izz="${(m/12) * (w*w + h*h)}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
<xacro:macro name="cylinder_inertia" params="m r h xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}" />
|
||||||
|
<mass value="${m}" />
|
||||||
|
<inertia ixx="${(m/12) * (3*r*r + h*h)}" ixy="0" ixz="0"
|
||||||
|
iyy="${(m/12) * (3*r*r + h*h)}" iyz="0"
|
||||||
|
izz="${(m/2) * (r*r)}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
<xacro:macro name="sphere_inertia" params="m r xyz rpy">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}" />
|
||||||
|
<mass value="${m}" />
|
||||||
|
<inertia ixx="${(2/5) * m * r * r}" ixy="0" ixz="0"
|
||||||
|
iyy="${(2/5) * m * r * r}" iyz="0"
|
||||||
|
izz="${(2/5) * m * r * r}" />
|
||||||
|
</inertial>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
</robot>
|
97
my_robot1_description/urdf_his/mobile_base.xacro
Normal file
97
my_robot1_description/urdf_his/mobile_base.xacro
Normal file
@ -0,0 +1,97 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="base_length" value="0.6" />
|
||||||
|
<xacro:property name="base_width" value="0.4" />
|
||||||
|
<xacro:property name="base_height" value="0.2" />
|
||||||
|
<xacro:property name="wheel_radius" value="0.1" />
|
||||||
|
<xacro:property name="wheel_length" value="0.05" />
|
||||||
|
|
||||||
|
<link name="base_footprint" />
|
||||||
|
|
||||||
|
<link name="base_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<box size="${base_length} ${base_width} ${base_height}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
<material name="blue" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<box size="${base_length} ${base_width} ${base_height}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 ${base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:box_inertia m="5.0" l="${2*base_length}" w="${2*base_width}" h="${2*base_height}"
|
||||||
|
xyz="0 0 ${base_height / 2.0}" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<xacro:macro name="wheel_link" params="prefix">
|
||||||
|
<link name="${prefix}_wheel_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="${pi / 2.0} 0 0" />
|
||||||
|
<material name="grey" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="${pi / 2.0} 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:cylinder_inertia m="1.0" r="${2*wheel_radius}" h="${2*wheel_length}"
|
||||||
|
xyz="0 0 0" rpy="${pi / 2.0} 0 0" />
|
||||||
|
</link>
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
<xacro:wheel_link prefix="right" />
|
||||||
|
<xacro:wheel_link prefix="left" />
|
||||||
|
|
||||||
|
<link name="caster_wheel_link">
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${wheel_radius / 2.0}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
<material name="grey" />
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${wheel_radius / 2.0}" />
|
||||||
|
</geometry>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</collision>
|
||||||
|
<xacro:sphere_inertia m="0.5" r="${2*wheel_radius / 2.0}"
|
||||||
|
xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="base_joint" type="fixed">
|
||||||
|
<parent link="base_footprint" />
|
||||||
|
<child link="base_link" />
|
||||||
|
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_right_wheel_joint" type="continuous">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="right_wheel_link" />
|
||||||
|
<origin xyz="${-base_length / 4.0} ${-(base_width + wheel_length) / 2.0} 0" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_left_wheel_joint" type="continuous">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="left_wheel_link" />
|
||||||
|
<origin xyz="${-base_length / 4.0} ${(base_width + wheel_length) / 2.0} 0" rpy="0 0 0" />
|
||||||
|
<axis xyz="0 1 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_caster_wheel_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="caster_wheel_link" />
|
||||||
|
<origin xyz="${base_length / 3.0} 0 ${-wheel_radius / 2.0}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
</robot>
|
42
my_robot1_description/urdf_his/mobile_base_gazebo.xacro
Normal file
42
my_robot1_description/urdf_his/mobile_base_gazebo.xacro
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<material>Gazebo/Blue</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="right_wheel_link">
|
||||||
|
<material>Gazebo/Grey</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="left_wheel_link">
|
||||||
|
<material>Gazebo/Grey</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="caster_wheel_link">
|
||||||
|
<material>Gazebo/Grey</material>
|
||||||
|
<mu1 value="0.1" />
|
||||||
|
<mu2 value="0.1" />
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
||||||
|
<!-- Update rate in Hz -->
|
||||||
|
<update_rate>50</update_rate>
|
||||||
|
<!-- wheels -->
|
||||||
|
<left_joint>base_left_wheel_joint</left_joint>
|
||||||
|
<right_joint>base_right_wheel_joint</right_joint>
|
||||||
|
<!-- kinematics -->
|
||||||
|
<wheel_separation>0.45</wheel_separation>
|
||||||
|
<wheel_diameter>0.2</wheel_diameter>
|
||||||
|
<!-- output -->
|
||||||
|
<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>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
18
my_robot1_description/urdf_his/my_robot.urdf.xacro
Normal file
18
my_robot1_description/urdf_his/my_robot.urdf.xacro
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:include filename="common_properties.xacro" />
|
||||||
|
<xacro:include filename="mobile_base.xacro" />
|
||||||
|
<xacro:include filename="mobile_base_gazebo.xacro" />
|
||||||
|
<xacro:include filename="arm.xacro" />
|
||||||
|
<xacro:include filename="arm_gazebo.xacro" />
|
||||||
|
|
||||||
|
<joint name="mobile_base_arm_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="arm_base_link" />
|
||||||
|
<origin xyz="${base_length / 4.0} 0 ${base_height}" rpy="0 0 0" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- <xacro:include filename="camera.xacro" /> -->
|
||||||
|
|
||||||
|
</robot>
|
8
my_robot1_description/urdf_his/standalone_arm.urdf.xacro
Normal file
8
my_robot1_description/urdf_his/standalone_arm.urdf.xacro
Normal file
@ -0,0 +1,8 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:include filename="common_properties.xacro" />
|
||||||
|
<xacro:include filename="arm.xacro" />
|
||||||
|
<xacro:include filename="arm_gazebo.xacro" />
|
||||||
|
|
||||||
|
</robot>
|
Loading…
Reference in New Issue
Block a user