This commit is contained in:
2018-08-02 00:56:02 -07:00
39 changed files with 1782 additions and 0 deletions

View File

@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(mr1718-arm-urdf_export)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@@ -0,0 +1 @@
controller_joint_names: ['shoulder', 'elbow', 'roll', 'wrist_base', 'wrist_pitch', 'wrist_roll', ]

View File

@@ -0,0 +1,26 @@
<launch>
<arg
name="model" />
<arg
name="gui"
default="False" />
<param
name="robot_description"
textfile="$(find mr1718-arm-urdf_export)/robots/mr1718-arm-urdf_export.urdf" />
<param
name="use_gui"
value="$(arg gui)" />
<node
name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find mr1718-arm-urdf_export)/urdf.rviz" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find mr1718-arm-urdf_export)/robots/mr1718-arm-urdf_export.urdf -urdf -model mr1718-arm-urdf_export"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

View File

@@ -0,0 +1,21 @@
<package>
<name>mr1718-arm-urdf_export</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for mr1718-arm-urdf_export</p>
<p>This package contains configuration data, 3D models and launch files
for mr1718-arm-urdf_export robot</p>
</description>
<author>me</author>
<maintainer email="me@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rviz</run_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>gazebo</run_depend>
<export>
<architecture_independent />
</export>
</package>

View File

@@ -0,0 +1,361 @@
<robot
name="mr1718-arm-urdf_export">
<link
name="base_link">
<inertial>
<origin
xyz="5.4755E-05 0.015543 0.0086991"
rpy="0 0 0" />
<mass
value="1.5519" />
<inertia
ixx="0.0045029"
ixy="-1.9571E-05"
ixz="1.1071E-05"
iyy="0.001083"
iyz="0.0012614"
izz="0.0038307" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="shoulder_link">
<inertial>
<origin
xyz="-0.0076779 0.072439 -0.00025927"
rpy="0 0 0" />
<mass
value="1.2323" />
<inertia
ixx="0.00071817"
ixy="8.2844E-05"
ixz="4.663E-06"
iyy="0.0012756"
iyz="3.6626E-06"
izz="0.0019919" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/shoulder_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/shoulder_link.STL" />
</geometry>
</collision>
</link>
<joint
name="shoulder"
type="continuous">
<origin
xyz="0 0.0025248 0.091246"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="shoulder_link" />
<axis
xyz="0 1 0" />
</joint>
<link
name="elbow_link">
<inertial>
<origin
xyz="0.052746 3.5254E-06 0.25018"
rpy="0 0 0" />
<mass
value="1.5164" />
<inertia
ixx="0.082218"
ixy="3.201E-09"
ixz="0.00060003"
iyy="0.082526"
iyz="-8.6916E-07"
izz="0.00030787" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/elbow_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/elbow_link.STL" />
</geometry>
</collision>
</link>
<joint
name="elbow"
type="continuous">
<origin
xyz="0.0335058907562339 0.0827436823988177 0"
rpy="0 0 0" />
<parent
link="shoulder_link" />
<child
link="elbow_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="roll_link">
<inertial>
<origin
xyz="-0.030978 -3.4831E-06 -0.0054534"
rpy="0 0 0" />
<mass
value="1.0721" />
<inertia
ixx="0.00049287"
ixy="3.3206E-08"
ixz="-3.6397E-06"
iyy="0.00051016"
iyz="-4.5289E-08"
izz="2.4367E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/roll_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/roll_link.STL" />
</geometry>
</collision>
</link>
<joint
name="roll"
type="continuous">
<origin
xyz="0 0 0.523621"
rpy="0 0 0" />
<parent
link="elbow_link" />
<child
link="roll_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="wrist_link">
<inertial>
<origin
xyz="-0.00095192 -4.7142E-05 0.25454"
rpy="0 0 0" />
<mass
value="0.60759" />
<inertia
ixx="0.0039577"
ixy="4.5025E-07"
ixz="5.7684E-05"
iyy="0.0042265"
iyz="1.2153E-06"
izz="0.00026882" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_base"
type="continuous">
<origin
xyz="-0.0345081407562338 0 0.048642197732"
rpy="0 0 0" />
<parent
link="roll_link" />
<child
link="wrist_link" />
<axis
xyz="0 0 1" />
</joint>
<link
name="wrist_pitch_link">
<inertial>
<origin
xyz="0.00095959 0.00027042 0.014957"
rpy="0 0 0" />
<mass
value="0.32143" />
<inertia
ixx="0.00011388"
ixy="-2.4963E-06"
ixz="2.1367E-06"
iyy="0.00018114"
iyz="1.3277E-06"
izz="6.9395E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_pitch_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_pitch_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_pitch"
type="continuous">
<origin
xyz="0 0 0.343027"
rpy="0 0 0" />
<parent
link="wrist_link" />
<child
link="wrist_pitch_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="wrist_roll_link">
<inertial>
<origin
xyz="-3.3391E-05 7.6495E-05 0.034573"
rpy="0 0 0" />
<mass
value="0.090203" />
<inertia
ixx="4.2212E-06"
ixy="9.452E-08"
ixz="1.6547E-08"
iyy="3.9599E-06"
iyz="-5.2152E-08"
izz="3.8149E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_roll_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_roll_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_roll"
type="continuous">
<origin
xyz="0 0 0.0227193855733502"
rpy="0 0 0" />
<parent
link="wrist_pitch_link" />
<child
link="wrist_roll_link" />
<axis
xyz="0 0 1" />
</joint>
</robot>

View File

@@ -0,0 +1,11 @@
moveit_setup_assistant_config:
URDF:
package: mr1718-arm-urdf_export
relative_path: robots/mr1718-arm-urdf_export.urdf
xacro_args: "--inorder "
SRDF:
relative_path: config/mr1718-arm-urdf_export.srdf
CONFIG:
author_name: Corwin Perren
author_email: caperren@gmail.com
generated_timestamp: 1533095742

View File

@@ -0,0 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(rover_arm_moveit_config)
find_package(catkin REQUIRED)
catkin_package()
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

View File

@@ -0,0 +1,9 @@
controller_list:
- name: fake_manipulator_controller
joints:
- shoulder
- elbow
- roll
- wrist_base
- wrist_pitch
- wrist_roll

View File

@@ -0,0 +1,34 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# 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:
elbow:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
roll:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
shoulder:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
wrist_base:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
wrist_pitch:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
wrist_roll:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0

View File

@@ -0,0 +1,5 @@
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3

View File

@@ -0,0 +1,48 @@
<?xml version="1.0" ?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="mr1718-arm-urdf_export">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="manipulator">
<chain base_link="base_link" tip_link="wrist_roll_link" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="straight_up" group="manipulator">
<joint name="elbow" value="-1.57" />
<joint name="roll" value="0" />
<joint name="shoulder" value="0" />
<joint name="wrist_base" value="0" />
<joint name="wrist_pitch" value="0" />
<joint name="wrist_roll" value="0" />
</group_state>
<group_state name="stowed" group="manipulator">
<joint name="elbow" value="-3.1415" />
<joint name="roll" value="3.1415" />
<joint name="shoulder" value="0" />
<joint name="wrist_base" value="1.57" />
<joint name="wrist_pitch" value="-1.57" />
<joint name="wrist_roll" value="0" />
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="gripper" parent_link="wrist_roll_link" group="manipulator" />
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="world" type="fixed" parent_frame="world" child_link="base_link" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="base_link" link2="roll_link" reason="Never" />
<disable_collisions link1="base_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="elbow_link" link2="roll_link" reason="Adjacent" />
<disable_collisions link1="elbow_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="roll_link" link2="shoulder_link" reason="Never" />
<disable_collisions link1="roll_link" link2="wrist_link" reason="Adjacent" />
<disable_collisions link1="roll_link" link2="wrist_pitch_link" reason="Never" />
<disable_collisions link1="roll_link" link2="wrist_roll_link" reason="Never" />
<disable_collisions link1="shoulder_link" link2="wrist_link" reason="Never" />
<disable_collisions link1="wrist_link" link2="wrist_pitch_link" reason="Adjacent" />
<disable_collisions link1="wrist_pitch_link" link2="wrist_roll_link" reason="Adjacent" />
</robot>

View File

@@ -0,0 +1,150 @@
planner_configs:
SBL:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
EST:
type: geometric::EST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LBKPIECE:
type: geometric::LBKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
BKPIECE:
type: geometric::BKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
KPIECE:
type: geometric::KPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
RRT:
type: geometric::RRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
RRTConnect:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstar:
type: geometric::RRTstar
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
TRRT:
type: geometric::TRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
max_states_failed: 10 # when to start increasing temp. default: 10
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
init_temperature: 10e-6 # initial temperature. default: 10e-6
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
PRM:
type: geometric::PRM
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
PRMstar:
type: geometric::PRMstar
FMT:
type: geometric::FMT
num_samples: 1000 # number of states that the planner should sample. default: 1000
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
nearest_k: 1 # use Knearest strategy. default: 1
cache_cc: 1 # use collision checking cache. default: 1
heuristics: 0 # activate cost to go heuristics. default: 0
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
BFMT:
type: geometric::BFMT
num_samples: 1000 # number of states that the planner should sample. default: 1000
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
nearest_k: 1 # use the Knearest strategy. default: 1
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
heuristics: 1 # activates cost to go heuristics. default: 1
cache_cc: 1 # use the collision checking cache. default: 1
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
PDST:
type: geometric::PDST
STRIDE:
type: geometric::STRIDE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
max_degree: 18 # max degree of a node in the GNAT. default: 12
min_degree: 12 # min degree of a node in the GNAT. default: 12
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
BiTRRT:
type: geometric::BiTRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
init_temperature: 100 # initial temperature. default: 100
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
LBTRRT:
type: geometric::LBTRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
epsilon: 0.4 # optimality approximation factor. default: 0.4
BiEST:
type: geometric::BiEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
ProjEST:
type: geometric::ProjEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LazyPRM:
type: geometric::LazyPRM
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
LazyPRMstar:
type: geometric::LazyPRMstar
SPARS:
type: geometric::SPARS
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 1000 # maximum consecutive failure limit. default: 1000
SPARStwo:
type: geometric::SPARStwo
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000
manipulator:
default_planner_config: NonekConfigDefault
planner_configs:
- SBLkConfigDefault
- ESTkConfigDefault
- LBKPIECEkConfigDefault
- BKPIECEkConfigDefault
- KPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- RRTstarkConfigDefault
- TRRTkConfigDefault
- PRMkConfigDefault
- PRMstarkConfigDefault
- FMTkConfigDefault
- BFMTkConfigDefault
- PDSTkConfigDefault
- STRIDEkConfigDefault
- BiTRRTkConfigDefault
- LBTRRTkConfigDefault
- BiESTkConfigDefault
- ProjESTkConfigDefault
- LazyPRMkConfigDefault
- LazyPRMstarkConfigDefault
- SPARSkConfigDefault
- SPARStwokConfigDefault
projection_evaluator: joints(shoulder,elbow)
longest_valid_segment_fraction: 0.005

View File

@@ -0,0 +1,15 @@
<launch>
<arg name="reset" default="false"/>
<!-- If not specified, we'll use a default database location -->
<arg name="moveit_warehouse_database_path" default="$(find rover_arm_moveit_config)/default_warehouse_mongo_db" />
<!-- Launch the warehouse with the configured database location -->
<include file="$(find rover_arm_moveit_config)/launch/warehouse.launch">
<arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" />
</include>
<!-- If we want to reset the database, run this node -->
<node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />
</launch>

View File

@@ -0,0 +1,57 @@
<launch>
<!-- By default, we do not start a database (it can be large) -->
<arg name="db" default="false" />
<!-- Allow user to specify database location -->
<arg name="db_path" default="$(find rover_arm_moveit_config)/default_warehouse_mongo_db" />
<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />
<!--
By default, hide joint_state_publisher's GUI
MoveIt!'s "demo" mode replaces the real robot driver with the joint_state_publisher.
The latter one maintains and publishes the current joint configuration of the simulated robot.
It also provides a GUI to move the simulated robot around "manually".
This corresponds to moving around the real robot without the use of MoveIt.
-->
<arg name="use_gui" default="false" />
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
<include file="$(find rover_arm_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<!-- If needed, broadcast static tf for robot root -->
<!-- We do not have a robot connected, so publish fake joint states -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/>
<rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam>
</node>
<!-- Given the published joint states, publish tf for the robot links -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
<include file="$(find rover_arm_moveit_config)/launch/move_group.launch">
<arg name="allow_trajectory_execution" value="true"/>
<arg name="fake_execution" value="true"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- Run Rviz and load the default config to see the state of the move_group node -->
<include file="$(find rover_arm_moveit_config)/launch/moveit_rviz.launch">
<arg name="config" value="true"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- If database loading was enabled, start mongodb as well -->
<include file="$(find rover_arm_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
</include>
</launch>

View File

@@ -0,0 +1,9 @@
<launch>
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
<param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/>
<!-- The rest of the params are specific to this plugin -->
<rosparam file="$(find rover_arm_moveit_config)/config/fake_controllers.yaml"/>
</launch>

View File

@@ -0,0 +1,17 @@
<launch>
<!-- See moveit_ros/visualization/doc/joystick.rst for documentation -->
<arg name="dev" default="/dev/input/js0" />
<!-- Launch joy node -->
<node pkg="joy" type="joy_node" name="joy">
<param name="dev" value="$(arg dev)" /> <!-- Customize this to match the location your joystick is plugged in on-->
<param name="deadzone" value="0.2" />
<param name="autorepeat_rate" value="40" />
<param name="coalesce_interval" value="0.025" />
</node>
<!-- Launch python interface -->
<node pkg="moveit_ros_visualization" type="moveit_joy.py" output="screen" name="moveit_joy"/>
</launch>

View File

@@ -0,0 +1,72 @@
<launch>
<include file="$(find rover_arm_moveit_config)/launch/planning_context.launch" />
<!-- GDB Debug Option -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix"
value="gdb -x $(find rover_arm_moveit_config)/launch/gdb_settings.gdb --ex run --args" />
<!-- Verbose Mode Option -->
<arg name="info" default="$(arg debug)" />
<arg unless="$(arg info)" name="command_args" value="" />
<arg if="$(arg info)" name="command_args" value="--debug" />
<!-- move_group settings -->
<arg name="allow_trajectory_execution" default="true"/>
<arg name="fake_execution" default="false"/>
<arg name="max_safe_path_cost" default="1"/>
<arg name="jiggle_fraction" default="0.05" />
<arg name="publish_monitored_planning_scene" default="true"/>
<!-- Planning Functionality -->
<include ns="move_group" file="$(find rover_arm_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="ompl" />
</include>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find rover_arm_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="mr1718-arm-urdf_export" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
<!-- Sensors Functionality -->
<include ns="move_group" file="$(find rover_arm_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_sensor_manager" value="mr1718-arm-urdf_export" />
</include>
<!-- Start the actual move_group node/action server -->
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<!-- Set the display variable, in case OpenGL code is used internally -->
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<!-- load these non-default MoveGroup capabilities -->
<!--
<param name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->
<!-- inhibit these default MoveGroup capabilities -->
<!--
<param name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->
<!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
</node>
</launch>

View File

@@ -0,0 +1,689 @@
Panels:
- Class: rviz/Displays
Help Height: 84
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
Splitter Ratio: 0.74256
Tree Height: 664
- Class: rviz/Help
Name: Help
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.03
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: moveit_rviz_plugin/MotionPlanning
Enabled: true
MoveIt_Goal_Tolerance: 0
MoveIt_Planning_Time: 5
MoveIt_Use_Constraint_Aware_IK: true
MoveIt_Warehouse_Host: 127.0.0.1
MoveIt_Warehouse_Port: 33829
Name: MotionPlanning
Planned Path:
Links:
base_bellow_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
double_stereo_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_kinect_ir_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_kinect_rgb_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_prosilica_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_plate_frame:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_tilt_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_elbow_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_forearm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_l_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_l_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_motor_accelerometer_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_palm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_r_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_r_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_shoulder_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_shoulder_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_upper_arm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_wrist_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_wrist_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser_tilt_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_elbow_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_forearm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_l_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_l_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_motor_accelerometer_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_palm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_r_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_r_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_shoulder_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_shoulder_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_upper_arm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_wrist_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_wrist_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
sensor_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
torso_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Loop Animation: true
Robot Alpha: 0.5
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 0.05 s
Trajectory Topic: move_group/display_planned_path
Planning Metrics:
Payload: 1
Show Joint Torques: false
Show Manipulability: false
Show Manipulability Index: false
Show Weight Limit: false
Planning Request:
Colliding Link Color: 255; 0; 0
Goal State Alpha: 1
Goal State Color: 250; 128; 0
Interactive Marker Size: 0
Joint Violation Color: 255; 0; 255
Planning Group: left_arm
Query Goal State: true
Query Start State: false
Show Workspace: false
Start State Alpha: 1
Start State Color: 0; 255; 0
Planning Scene Topic: move_group/monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Color: 50; 230; 50
Scene Display Time: 0.2
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Scene Robot:
Attached Body Color: 150; 50; 150
Links:
base_bellow_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
bl_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
br_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
double_stereo_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_l_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_r_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_caster_rotation_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_kinect_ir_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_kinect_rgb_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_mount_prosilica_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_plate_frame:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_tilt_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_elbow_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_forearm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_l_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_l_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_motor_accelerometer_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_palm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_r_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_gripper_r_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_shoulder_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_shoulder_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_upper_arm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_wrist_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
l_wrist_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser_tilt_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_elbow_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_forearm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_l_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_l_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_motor_accelerometer_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_palm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_r_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_gripper_r_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_shoulder_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_shoulder_pan_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_upper_arm_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_wrist_flex_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_wrist_roll_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
sensor_mount_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
torso_lift_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Robot Alpha: 0.5
Show Scene Robot: true
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: /base_link
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
Value: true
Views:
Current:
Class: rviz/XYOrbit
Distance: 2.9965
Focal Point:
X: 0.113567
Y: 0.10592
Z: 2.23518e-07
Name: Current View
Near Clip Distance: 0.01
Pitch: 0.509797
Target Frame: /base_link
Value: XYOrbit (rviz)
Yaw: 5.65995
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1337
Help:
collapsed: false
Hide Left Dock: false
Hide Right Dock: false
Motion Planning:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Views:
collapsed: false
Width: 1828
X: 459
Y: -243

View File

@@ -0,0 +1,16 @@
<launch>
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="config" default="false" />
<arg unless="$(arg config)" name="command_args" value="" />
<arg if="$(arg config)" name="command_args" value="-d $(find rover_arm_moveit_config)/launch/moveit.rviz" />
<node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false"
args="$(arg command_args)" output="screen">
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/kinematics.yaml"/>
</node>
</launch>

View File

@@ -0,0 +1,22 @@
<launch>
<!-- OMPL Plugin for MoveIt! -->
<arg name="planning_plugin" value="ompl_interface/OMPLPlanner" />
<!-- The request adapters (plugins) used when planning with OMPL.
ORDER MATTERS -->
<arg name="planning_adapters" value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints" />
<arg name="start_state_max_bounds_error" value="0.1" />
<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="$(arg planning_adapters)" />
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/ompl_planning.yaml"/>
</launch>

View File

@@ -0,0 +1,24 @@
<launch>
<!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
<arg name="load_robot_description" default="false"/>
<!-- The name of the parameter under which the URDF is loaded -->
<arg name="robot_description" default="robot_description"/>
<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" textfile="$(find mr1718-arm-urdf_export)/robots/mr1718-arm-urdf_export.urdf"/>
<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find rover_arm_moveit_config)/config/mr1718-arm-urdf_export.srdf" />
<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/joint_limits.yaml"/>
</group>
<!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
<group ns="$(arg robot_description)_kinematics">
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/kinematics.yaml"/>
</group>
</launch>

View File

@@ -0,0 +1,10 @@
<launch>
<!-- This file makes it easy to include different planning pipelines;
It is assumed that all planning pipelines are named XXX_planning_pipeline.launch -->
<arg name="pipeline" default="ompl" />
<include file="$(find rover_arm_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml" />
</launch>

View File

@@ -0,0 +1,22 @@
<launch>
<!-- This argument must specify the list of .cfg files to process for benchmarking -->
<arg name="cfg" />
<!-- Load URDF -->
<include file="$(find rover_arm_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<!-- Start the database -->
<include file="$(find rover_arm_moveit_config)/launch/warehouse.launch">
<arg name="moveit_warehouse_database_path" value="moveit_ompl_benchmark_warehouse"/>
</include>
<!-- Start Benchmark Executable -->
<node name="$(anon moveit_benchmark)" pkg="moveit_ros_benchmarks" type="moveit_run_benchmark" args="$(arg cfg) --benchmark-planners" respawn="false" output="screen">
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/kinematics.yaml"/>
<rosparam command="load" file="$(find rover_arm_moveit_config)/config/ompl_planning.yaml"/>
</node>
</launch>

View File

@@ -0,0 +1,14 @@
<launch>
<!-- This file makes it easy to include the settings for sensor managers -->
<!-- Params for the octomap monitor -->
<!-- <param name="octomap_frame" type="string" value="some frame in which the robot moves" /> -->
<param name="octomap_resolution" type="double" value="0.025" />
<param name="max_range" type="double" value="5.0" />
<!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter -->
<arg name="moveit_sensor_manager" default="mr1718-arm-urdf_export" />
<include file="$(find rover_arm_moveit_config)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" />
</launch>

View File

@@ -0,0 +1,15 @@
<!-- Re-launch the MoveIt Setup Assistant with this configuration package already loaded -->
<launch>
<!-- Debug Info -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<!-- Run -->
<node pkg="moveit_setup_assistant" type="moveit_setup_assistant" name="moveit_setup_assistant"
args="--config_pkg=rover_arm_moveit_config"
launch-prefix="$(arg launch_prefix)"
output="screen" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<!-- This file makes it easy to include the settings for trajectory execution -->
<!-- Flag indicating whether MoveIt! is allowed to load/unload or switch controllers -->
<arg name="moveit_manage_controllers" default="true"/>
<param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
<!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
<param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
<!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
<param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
<!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->
<param name="trajectory_execution/allowed_start_tolerance" value="0.01"/> <!-- default 0.01 -->
<!-- Load the robot specific controller manager; this sets the moveit_controller_manager ROS parameter -->
<arg name="moveit_controller_manager" default="mr1718-arm-urdf_export" />
<include file="$(find rover_arm_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" />
</launch>

View File

@@ -0,0 +1,15 @@
<launch>
<!-- The path to the database must be specified -->
<arg name="moveit_warehouse_database_path" />
<!-- Load warehouse parameters -->
<include file="$(find rover_arm_moveit_config)/launch/warehouse_settings.launch.xml" />
<!-- Run the DB server -->
<node name="$(anon mongo_wrapper_ros)" cwd="ROS_HOME" type="mongo_wrapper_ros.py" pkg="warehouse_ros_mongo">
<param name="overwrite" value="false"/>
<param name="database_path" value="$(arg moveit_warehouse_database_path)" />
</node>
</launch>

View File

@@ -0,0 +1,16 @@
<launch>
<!-- Set the parameters for the warehouse and run the mongodb server. -->
<!-- The default DB port for moveit (not default MongoDB port to avoid potential conflicts) -->
<arg name="moveit_warehouse_port" default="33829" />
<!-- The default DB host for moveit -->
<arg name="moveit_warehouse_host" default="localhost" />
<!-- Set parameters for the warehouse -->
<param name="warehouse_port" value="$(arg moveit_warehouse_port)"/>
<param name="warehouse_host" value="$(arg moveit_warehouse_host)"/>
<param name="warehouse_exec" value="mongod" />
<param name="warehouse_plugin" value="warehouse_ros_mongo::MongoDatabaseConnection" />
</launch>

View File

@@ -0,0 +1,33 @@
<package>
<name>rover_arm_moveit_config</name>
<version>0.3.0</version>
<description>
An automatically generated package with all the configuration and launch files for using the mr1718-arm-urdf_export with the MoveIt! Motion Planning Framework
</description>
<author email="caperren@gmail.com">Corwin Perren</author>
<maintainer email="caperren@gmail.com">Corwin Perren</maintainer>
<license>BSD</license>
<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/ros-planning/moveit/issues</url>
<url type="repository">https://github.com/ros-planning/moveit</url>
<buildtool_depend>catkin</buildtool_depend>
<run_depend>moveit_ros_move_group</run_depend>
<run_depend>moveit_fake_controller_manager</run_depend>
<run_depend>moveit_kinematics</run_depend>
<run_depend>moveit_planners_ompl</run_depend>
<run_depend>moveit_ros_visualization</run_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>xacro</run_depend>
<!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->
<!-- <run_depend>warehouse_ros_mongo</run_depend> -->
<build_depend>mr1718-arm-urdf_export</build_depend>
<run_depend>mr1718-arm-urdf_export</run_depend>
</package>