Skip to content
This repository was archived by the owner on Oct 17, 2025. It is now read-only.

Commit 4039a06

Browse files
committed
Added moveit2 demo
Signed-off-by: ahcorde <[email protected]>
1 parent b61b137 commit 4039a06

File tree

12 files changed

+903
-0
lines changed

12 files changed

+903
-0
lines changed

rrbot_description/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
cmake_minimum_required(VERSION 3.10.2)
2+
project(rrbot_description)
3+
find_package(ament_cmake REQUIRED)
4+
5+
ament_package()
6+
7+
install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})

rrbot_description/package.xml

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
<?xml version="1.0"?>
2+
<package format="3">
3+
<name>rrbot_description</name>
4+
<version>0.0.0</version>
5+
<description>Rrbot Resources used for MoveIt testing</description>
6+
7+
<author email="[email protected]">Alejandro</author>
8+
9+
<maintainer email="[email protected]">Alejandro</maintainer>
10+
11+
<license>BSD</license>
12+
13+
<buildtool_depend>ament_cmake</buildtool_depend>
14+
15+
<export>
16+
<build_type>ament_cmake</build_type>
17+
</export>
18+
</package>

rrbot_description/urdf/rrbot.urdf

Lines changed: 214 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,214 @@
1+
<?xml version="1.0" ?>
2+
<!-- =================================================================================== -->
3+
<!-- | This document was autogenerated by xacro from single_rrbot.urdf.xacro | -->
4+
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
5+
<!-- =================================================================================== -->
6+
<robot name="single_rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
7+
<!-- Import your models -->
8+
<material name="RRBOT/black">
9+
<color rgba="0.0 0.0 0.0 1.0"/>
10+
</material>
11+
<material name="RRBOT/blue">
12+
<color rgba="0.0 0.0 0.8 1.0"/>
13+
</material>
14+
<material name="RRBOT/green">
15+
<color rgba="0.0 0.8 0.0 1.0"/>
16+
</material>
17+
<material name="RRBOT/grey">
18+
<color rgba="0.2 0.2 0.2 1.0"/>
19+
</material>
20+
<material name="RRBOT/orange">
21+
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
22+
</material>
23+
<material name="RRBOT/brown">
24+
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
25+
</material>
26+
<material name="RRBOT/red">
27+
<color rgba="0.8 0.0 0.0 1.0"/>
28+
</material>
29+
<material name="RRBOT/white">
30+
<color rgba="1.0 1.0 1.0 1.0"/>
31+
</material>
32+
<!-- Build your comprehensive robot -->
33+
<link name="world"/>
34+
<gazebo reference="world">
35+
<static>true</static>
36+
</gazebo>
37+
<joint name="single_rrbot_fixed" type="fixed">
38+
<origin rpy="0 0 0" xyz="0 0 0"/>
39+
<parent link="world"/>
40+
<child link="single_rrbot_link1"/>
41+
</joint>
42+
<link name="single_rrbot_link1">
43+
<collision>
44+
<origin rpy="0 0 0" xyz="0 0 1.0"/>
45+
<geometry>
46+
<box size="0.1 0.1 2"/>
47+
</geometry>
48+
</collision>
49+
<visual>
50+
<origin rpy="0 0 0" xyz="0 0 1.0"/>
51+
<geometry>
52+
<box size="0.1 0.1 2"/>
53+
</geometry>
54+
<material name="RRBOT/orange"/>
55+
</visual>
56+
<inertial>
57+
<origin rpy="0 0 0" xyz="0 0 1.0"/>
58+
<mass value="1"/>
59+
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
60+
</inertial>
61+
</link>
62+
<joint name="single_rrbot_joint1" type="continuous">
63+
<parent link="single_rrbot_link1"/>
64+
<child link="single_rrbot_link2"/>
65+
<origin rpy="0 0 0" xyz="0 0.1 1.95"/>
66+
<axis xyz="0 1 0"/>
67+
<dynamics damping="0.7"/>
68+
</joint>
69+
70+
<gazebo>
71+
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
72+
<robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
73+
<parameters>/home/ahcorde/ros2_control_ws_foxy/rrbot.yaml</parameters>
74+
<control_period>0.001</control_period>
75+
</plugin>
76+
</gazebo>
77+
78+
<link name="single_rrbot_link2">
79+
<collision>
80+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
81+
<geometry>
82+
<box size="0.1 0.1 1"/>
83+
</geometry>
84+
</collision>
85+
<visual>
86+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
87+
<geometry>
88+
<box size="0.1 0.1 1"/>
89+
</geometry>
90+
<material name="RRBOT/black"/>
91+
</visual>
92+
<inertial>
93+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
94+
<mass value="1"/>
95+
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
96+
</inertial>
97+
</link>
98+
<joint name="single_rrbot_joint2" type="continuous">
99+
<parent link="single_rrbot_link2"/>
100+
<child link="single_rrbot_link3"/>
101+
<origin rpy="0 0 0" xyz="0 0.1 0.9"/>
102+
<axis xyz="0 1 0"/>
103+
<dynamics damping="0.7"/>
104+
</joint>
105+
<link name="single_rrbot_link3">
106+
<collision>
107+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
108+
<geometry>
109+
<box size="0.1 0.1 1"/>
110+
</geometry>
111+
</collision>
112+
<visual>
113+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
114+
<geometry>
115+
<box size="0.1 0.1 1"/>
116+
</geometry>
117+
<material name="RRBOT/orange"/>
118+
</visual>
119+
<inertial>
120+
<origin rpy="0 0 0" xyz="0 0 0.45"/>
121+
<mass value="1"/>
122+
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
123+
</inertial>
124+
</link>
125+
<joint name="single_rrbot_hokuyo_joint" type="fixed">
126+
<axis xyz="0 1 0"/>
127+
<origin rpy="0 0 0" xyz="0 0 0.975"/>
128+
<parent link="single_rrbot_link3"/>
129+
<child link="single_rrbot_hokuyo_link"/>
130+
</joint>
131+
<link name="single_rrbot_hokuyo_link">
132+
<collision>
133+
<origin rpy="0 0 0" xyz="0 0 0"/>
134+
<geometry>
135+
<box size="0.1 0.1 0.1"/>
136+
</geometry>
137+
</collision>
138+
<visual>
139+
<origin rpy="0 0 0" xyz="0 0 0"/>
140+
<geometry>
141+
<box size="0.1 0.1 0.1"/>
142+
</geometry>
143+
</visual>
144+
<inertial>
145+
<mass value="1e-5"/>
146+
<origin rpy="0 0 0" xyz="0 0 0"/>
147+
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
148+
</inertial>
149+
</link>
150+
<joint name="single_rrbot_camera_joint" type="fixed">
151+
<axis xyz="0 1 0"/>
152+
<origin rpy="0 0 0" xyz="0.05 0 0.9"/>
153+
<parent link="single_rrbot_link3"/>
154+
<child link="single_rrbot_camera_link"/>
155+
</joint>
156+
<link name="single_rrbot_camera_link">
157+
<collision>
158+
<origin rpy="0 0 0" xyz="0 0 0"/>
159+
<geometry>
160+
<box size="0.05 0.05 0.05"/>
161+
</geometry>
162+
</collision>
163+
<visual>
164+
<origin rpy="0 0 0" xyz="0 0 0"/>
165+
<geometry>
166+
<box size="0.05 0.05 0.05"/>
167+
</geometry>
168+
<material name="RRBOT/red"/>
169+
</visual>
170+
<inertial>
171+
<mass value="1e-5"/>
172+
<origin rpy="0 0 0" xyz="0 0 0"/>
173+
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
174+
</inertial>
175+
</link>
176+
<transmission name="single_rrbot_tran1">
177+
<type>transmission_interface/SimpleTransmission</type>
178+
<joint name="single_rrbot_joint1">
179+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
180+
</joint>
181+
<actuator name="single_rrbot_motor1">
182+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
183+
<mechanicalReduction>1</mechanicalReduction>
184+
</actuator>
185+
</transmission>
186+
<transmission name="single_rrbot_tran2">
187+
<type>transmission_interface/SimpleTransmission</type>
188+
<joint name="single_rrbot_joint2">
189+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
190+
</joint>
191+
<actuator name="single_rrbot_motor2">
192+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
193+
<mechanicalReduction>1</mechanicalReduction>
194+
</actuator>
195+
</transmission>
196+
<gazebo reference="single_rrbot_link1">
197+
<material>Gazebo/Orange</material>
198+
</gazebo>
199+
<gazebo reference="single_rrbot_link2">
200+
<mu1>0.2</mu1>
201+
<mu2>0.2</mu2>
202+
<material>Gazebo/Black</material>
203+
</gazebo>
204+
<gazebo reference="single_rrbot_link3">
205+
<mu1>0.2</mu1>
206+
<mu2>0.2</mu2>
207+
<material>Gazebo/Orange</material>
208+
</gazebo>
209+
<gazebo reference="single_rrbot_camera_link">
210+
<mu1>0.2</mu1>
211+
<mu2>0.2</mu2>
212+
<material>Gazebo/Red</material>
213+
</gazebo>
214+
</robot>

rrbot_moveit_config/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
cmake_minimum_required(VERSION 3.10.2)
2+
project(rrbot_moveit_config)
3+
find_package(ament_cmake REQUIRED)
4+
5+
ament_package()
6+
7+
install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME})
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
rrbot_arm:
2+
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
3+
kinematics_solver_search_resolution: 0.005
4+
kinematics_solver_timeout: 0.005
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
run_moveit_cpp:
2+
ros__parameters:
3+
planning_scene_monitor_options:
4+
name: "planning_scene_monitor"
5+
robot_description: "robot_description"
6+
joint_state_topic: "/joint_states"
7+
attached_collision_object_topic: "/moveit_cpp/planning_scene_monitor"
8+
publish_planning_scene_topic: "/moveit_cpp/publish_planning_scene"
9+
monitored_planning_scene_topic: "/moveit_cpp/monitored_planning_scene"
10+
wait_for_initial_state_timeout: 10.0
11+
12+
planning_pipelines:
13+
#namespace: "moveit_cpp" # optional, default is ~
14+
pipeline_names: ["ompl"]
15+
16+
plan_request_params:
17+
planning_attempts: 10
18+
planning_pipeline: ompl
19+
max_velocity_scaling_factor: 1.0
20+
max_acceleration_scaling_factor: 1.0

0 commit comments

Comments
 (0)