Skip to content
Merged
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
48 changes: 48 additions & 0 deletions examples/dave_demo_launch/launch/dave_oberon7_moveit.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
<?xml version="1.0"?>
<launch>
<!-- <arg name="world_name" default="worlds/empty.world"/> -->
<arg name="world_name" default="$(find dave_worlds)/worlds/dave_ocean_waves.world"/>
<arg name="joy_id" default="0"/>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>

<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true"/>
</include>

<!-- use ned frame north east down -->
<include file="$(find uuv_assistants)/launch/publish_world_ned_frame.launch"/>

<include file="$(find rexrov_description)/launch/upload_rexrov_oberon7_moveit.launch"/>

<include file="$(find oberon7_gazebo)/launch/controller_utils.launch"/>

<!-- Start this controller -->
<rosparam file="$(find oberon7_gazebo)/controller/arm_controller_oberon7_l.yaml" command="load"/>
<node name="arm_controller_l_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller_l" respawn="false" output="screen"/>

<rosparam file="$(find oberon7_gazebo)/controller/arm_controller_oberon7_r.yaml" command="load"/>
<node name="arm_controller_r_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller_r" respawn="false" output="screen"/>

<!-- Start another controller -->
<rosparam file="$(find oberon7_gazebo)/controller/hand_controller_oberon7_l.yaml" command="load"/>
<node name="hand_controller_l_spawner" pkg="controller_manager" type="controller_manager" args="spawn hand_controller_l" respawn="false" output="screen"/>

<rosparam file="$(find oberon7_gazebo)/controller/hand_controller_oberon7_r.yaml" command="load"/>
<node name="hand_controller_r_spawner" pkg="controller_manager" type="controller_manager" args="spawn hand_controller_r" respawn="false" output="screen"/>

<!-- Load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller"/>

<include file="$(find uuv_control_cascaded_pid)/launch/joy_velocity.launch">
<arg name="uuv_name" value="rexrov" />
<arg name="model_name" value="rexrov" />
<arg name="joy_id" value="$(arg joy_id)"/>
</include>
</launch>
39 changes: 39 additions & 0 deletions examples/dave_demo_launch/launch/dave_two_arm_demo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<launch>
<param name="use_sim_time" value="true"/>
<arg name="robot_name"/>

<!-- <arg name="init_pose"/> -->
<!-- <arg name="parent" default="world"/> -->

<arg name="xyzpos" default="0.0 0.0 2.0"/>
<arg name="parent" default="world"/>

<arg name="paused" default="false"/>
<arg name="gui" default="true"/>

<param name="robot_description" command="$(find xacro)/xacro '$(find oberon7_description)/urdf/oberon7_robot.urdf.xacro'"/>

<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="worlds/empty.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gui)"/>
</include>

<group ns="robot1">
<param name="tf_prefix" value="robot1_tf"/>
<include file="$(find oberon7_gazebo)/launch/oberon7_multi.launch">
<arg name="xyzpos" value="0.0 0.0 2.0"/>
<arg name="parent" value="$(arg parent)"/>
<arg name="robot_name" value="robot1"/>
</include>
</group>

<group ns="robot2">
<param name="tf_prefix" value="robot2_tf"/>
<include file="$(find oberon7_gazebo)/launch/oberon7_multi.launch">
<arg name="xyzpos" value="0 2.0 2.0"/>
<arg name="parent" value="$(arg parent)"/>
<arg name="robot_name" value="robot2"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<launch>

<arg name="namespace" default="rexrov"/>
<arg name="debug" default="false"/>

<param name="robot_description" command="$(find xacro)/xacro '$(find rexrov_description)/urdf/rexrov_robot.urdf.xacro' inertial_reference_frame:=world"/>


<node name="urdf_spawner" pkg="uuv_descriptions" type="spawn_model" respawn="false" output="screen" args="-urdf -z -20 -model $(arg namespace) -param robot_description"/>

<!-- <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen">
<param name="robot_description" value="/$(arg namespace)/robot_description" />
</node> -->

</launch>
52 changes: 52 additions & 0 deletions urdf/robots/rexrov_description/urdf/rexrov_robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="rexrov">
<xacro:arg name="namespace" default="rexrov"/>
<xacro:arg name="inertial_reference_frame" default="world"/>
<xacro:arg name="debug" default="false"/>

<xacro:include filename="$(find rexrov_description)/urdf/rexrov_base.xacro"/>
<xacro:include filename="$(find uuv_descriptions)/urdf/rexrov.gazebo.xacro"/>
<!-- <xacro:include filename="$(find dave_oberon7_description)/urdf/serial_arm.gazebo.xacro"/> -->
<!-- <xacro:include filename="$(find oberon7_description)/urdf/parameters/serial_arm.xacro"/> -->

<!-- <xacro:include filename="$(find dave_oberon7_description)/urdf/oberon7_default.xacro"/> -->
<xacro:include filename="$(find oberon7_description)/urdf/common.gazebo.xacro"/>
<xacro:include filename="$(find oberon7_description)/urdf/oberon7.urdf.xacro"/>

<xacro:rexrov_base namespace="$(arg namespace)" inertial_reference_frame="$(arg inertial_reference_frame)">
<!-- The underwater object plugin is given as an input block parameter to
allow the addition of external models of manipulator units -->
<gazebo>
<plugin name="uuv_plugin" filename="libuuv_underwater_object_ros_plugin.so">
<fluid_density>1028.0</fluid_density>
<flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>
<debug>$(arg debug)</debug>
<!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
<xacro:rexrov_hydro_model namespace="$(arg namespace)"/>
<!-- <xacro:oberon7_hydro_model namespace="oberon7"/> -->
</plugin>
</gazebo>
</xacro:rexrov_base>

<!-- oberon7 -->
<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- <xacro:include filename="$(find oberon7_description)/urdf/common.gazebo.xacro"/> -->
<!-- <xacro:include filename="$(find oberon7_description)/urdf/oberon7.urdf.xacro"/> -->

<xacro:oberon7_arm transmission_hw_interface="$(arg transmission_hw_interface)" namespace="oberon7_r"/>
<xacro:oberon7_arm transmission_hw_interface="$(arg transmission_hw_interface)" namespace="oberon7_l"/>

<joint name="oberon7_r_anchor" type="fixed">
<parent link="$(arg namespace)/base_link"/>
<child link="oberon7_r/base"/>
<origin rpy="0 0 0" xyz="1.3 -0.5 -0.615"/>
<!-- <origin rpy="0 0 0" xyz="0 0 2.0"/> -->
</joint>
<joint name="oberon7_l_anchor" type="fixed">
<parent link="$(arg namespace)/base_link"/>
<child link="oberon7_l/base"/>
<origin rpy="0 0 0" xyz="1.3 0.5 -0.615"/>
</joint>

</robot>
11 changes: 11 additions & 0 deletions urdf/robots/rexrov_oberon7_moveit/.setup_assistant
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
moveit_setup_assistant_config:
URDF:
package: rexrov_description
relative_path: urdf/rexrov_robot.urdf.xacro
xacro_args: ""
SRDF:
relative_path: config/rexrov.srdf
CONFIG:
author_name: c
author_email: c@c.com
generated_timestamp: 1644625029
38 changes: 38 additions & 0 deletions urdf/robots/rexrov_oberon7_moveit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
cmake_minimum_required(VERSION 3.1.3)
project(rexrov_oberon7_moveit)
find_package(catkin REQUIRED)

#if(NOT "${CMAKE_VERSION}" VERSION_LESS "3.16")
# set(CMAKE_CXX_STANDARD 17)
# set(CMAKE_CXX_STANDARD_REQUIRED ON)
#else()
add_compile_options(-std=c++11)
#endif()



find_package(catkin REQUIRED COMPONENTS)

find_package(gazebo REQUIRED)
find_package(roscpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(Eigen3 REQUIRED)

catkin_package(
INCLUDE_DIRS
LIBRARIES
CATKIN_DEPENDS
)

include_directories(${roscpp_INCLUDE_DIRS})
include_directories(${std_msgs_INCLUDE_DIRS})
include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS})
include_directories(
${catkin_INCLUDE_DIRS}
${GAZEBO_INCLUDE_DIRS}
)

install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
cartesian_limits:
max_trans_vel: 1
max_trans_acc: 2.25
max_trans_dec: -5
max_rot_vel: 1.57
18 changes: 18 additions & 0 deletions urdf/robots/rexrov_oberon7_moveit/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
smoothness_cost_weight: 0.1
obstacle_cost_weight: 1.0
learning_rate: 0.01
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
ridge_factor: 0.01
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
joint_update_limit: 0.1
collision_clearance: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
38 changes: 38 additions & 0 deletions urdf/robots/rexrov_oberon7_moveit/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
controller_list:
- name: fake_arm_l_controller
type: $(arg fake_execution_type)
joints:
- oberon7_l/azimuth
- oberon7_l/shoulder
- oberon7_l/elbow
- oberon7_l/roll
- oberon7_l/pitch
- oberon7_l/wrist
- name: fake_arm_r_controller
type: $(arg fake_execution_type)
joints:
- oberon7_r/azimuth
- oberon7_r/shoulder
- oberon7_r/elbow
- oberon7_r/roll
- oberon7_r/pitch
- oberon7_r/wrist
- name: fake_hand_l_controller
type: $(arg fake_execution_type)
joints:
- oberon7_l/finger_left_joint
- oberon7_l/finger_tip_left_joint
- oberon7_l/finger_right_joint
- oberon7_l/finger_tip_right_joint
- name: fake_hand_r_controller
type: $(arg fake_execution_type)
joints:
- oberon7_r/finger_left_joint
- oberon7_r/finger_tip_left_joint
- oberon7_r/finger_right_joint
- oberon7_r/finger_tip_right_joint
initial: # Define initial robot poses per group
# - group: arm_l
# pose: home

[]
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Publish joint_states
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
110 changes: 110 additions & 0 deletions urdf/robots/rexrov_oberon7_moveit/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
oberon7_l/azimuth:
has_velocity_limits: true
max_velocity: 0.17
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/elbow:
has_velocity_limits: true
max_velocity: 0.13
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/finger_left_joint:
has_velocity_limits: true
max_velocity: 0.15
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/finger_right_joint:
has_velocity_limits: true
max_velocity: 0.15
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/finger_tip_left_joint:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/finger_tip_right_joint:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/pitch:
has_velocity_limits: true
max_velocity: 0.26
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/roll:
has_velocity_limits: true
max_velocity: 0.08500000000000001
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/shoulder:
has_velocity_limits: true
max_velocity: 0.17
has_acceleration_limits: false
max_acceleration: 0
oberon7_l/wrist:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/azimuth:
has_velocity_limits: true
max_velocity: 0.17
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/elbow:
has_velocity_limits: true
max_velocity: 0.13
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/finger_left_joint:
has_velocity_limits: true
max_velocity: 0.15
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/finger_right_joint:
has_velocity_limits: true
max_velocity: 0.15
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/finger_tip_left_joint:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/finger_tip_right_joint:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/pitch:
has_velocity_limits: true
max_velocity: 0.26
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/roll:
has_velocity_limits: true
max_velocity: 0.08500000000000001
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/shoulder:
has_velocity_limits: true
max_velocity: 0.17
has_acceleration_limits: false
max_acceleration: 0
oberon7_r/wrist:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
Loading