Skip to content
This repository was archived by the owner on Oct 17, 2025. It is now read-only.
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions rrbot_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
cmake_minimum_required(VERSION 3.10.2)
project(rrbot_description)
find_package(ament_cmake REQUIRED)

ament_package()

install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})
18 changes: 18 additions & 0 deletions rrbot_description/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<package format="3">
<name>rrbot_description</name>
<version>0.0.0</version>
<description>Rrbot Resources used for MoveIt testing</description>

<author email="[email protected]">Alejandro</author>

<maintainer email="[email protected]">Alejandro</maintainer>

<license>BSD</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
214 changes: 214 additions & 0 deletions rrbot_description/urdf/rrbot.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,214 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from single_rrbot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="single_rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Import your models -->
<material name="RRBOT/black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="RRBOT/blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="RRBOT/green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="RRBOT/grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="RRBOT/orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="RRBOT/brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="RRBOT/red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="RRBOT/white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<!-- Build your comprehensive robot -->
<link name="world"/>
<gazebo reference="world">
<static>true</static>
</gazebo>
<joint name="single_rrbot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="single_rrbot_link1"/>
</joint>
<link name="single_rrbot_link1">
<collision>
<origin rpy="0 0 0" xyz="0 0 1.0"/>
<geometry>
<box size="0.1 0.1 2"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 1.0"/>
<geometry>
<box size="0.1 0.1 2"/>
</geometry>
<material name="RRBOT/orange"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 1.0"/>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="single_rrbot_joint1" type="continuous">
<parent link="single_rrbot_link1"/>
<child link="single_rrbot_link2"/>
<origin rpy="0 0 0" xyz="0 0.1 1.95"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
</joint>

<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
<parameters>/home/ahcorde/ros2_control_ws_foxy/rrbot.yaml</parameters>
<control_period>0.001</control_period>
</plugin>
</gazebo>

<link name="single_rrbot_link2">
<collision>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<geometry>
<box size="0.1 0.1 1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<geometry>
<box size="0.1 0.1 1"/>
</geometry>
<material name="RRBOT/black"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="single_rrbot_joint2" type="continuous">
<parent link="single_rrbot_link2"/>
<child link="single_rrbot_link3"/>
<origin rpy="0 0 0" xyz="0 0.1 0.9"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
</joint>
<link name="single_rrbot_link3">
<collision>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<geometry>
<box size="0.1 0.1 1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<geometry>
<box size="0.1 0.1 1"/>
</geometry>
<material name="RRBOT/orange"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.45"/>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="single_rrbot_hokuyo_joint" type="fixed">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0 0 0.975"/>
<parent link="single_rrbot_link3"/>
<child link="single_rrbot_hokuyo_link"/>
</joint>
<link name="single_rrbot_hokuyo_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="single_rrbot_camera_joint" type="fixed">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.05 0 0.9"/>
<parent link="single_rrbot_link3"/>
<child link="single_rrbot_camera_link"/>
</joint>
<link name="single_rrbot_camera_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="RRBOT/red"/>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<transmission name="single_rrbot_tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="single_rrbot_joint1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="single_rrbot_motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="single_rrbot_tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="single_rrbot_joint2">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="single_rrbot_motor2">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="single_rrbot_link1">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="single_rrbot_link2">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="single_rrbot_link3">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="single_rrbot_camera_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Red</material>
</gazebo>
</robot>
7 changes: 7 additions & 0 deletions rrbot_moveit_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
cmake_minimum_required(VERSION 3.10.2)
project(rrbot_moveit_config)
find_package(ament_cmake REQUIRED)

ament_package()

install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME})
4 changes: 4 additions & 0 deletions rrbot_moveit_config/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
rrbot_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
20 changes: 20 additions & 0 deletions rrbot_moveit_config/config/moveit_cpp.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
run_moveit_cpp:
ros__parameters:
planning_scene_monitor_options:
name: "planning_scene_monitor"
robot_description: "robot_description"
joint_state_topic: "/joint_states"
attached_collision_object_topic: "/moveit_cpp/planning_scene_monitor"
publish_planning_scene_topic: "/moveit_cpp/publish_planning_scene"
monitored_planning_scene_topic: "/moveit_cpp/monitored_planning_scene"
wait_for_initial_state_timeout: 10.0

planning_pipelines:
#namespace: "moveit_cpp" # optional, default is ~
pipeline_names: ["ompl"]

plan_request_params:
planning_attempts: 10
planning_pipeline: ompl
max_velocity_scaling_factor: 1.0
max_acceleration_scaling_factor: 1.0
Loading