Skip to content
Snippets Groups Projects
Unverified Commit e33dca94 authored by Nadia Hammoudeh García's avatar Nadia Hammoudeh García Committed by GitHub
Browse files

Merge branch 'kinetic-devel' into fixMeshes

parents d1da6828 c5a65a5d
Branches
No related merge requests found
......@@ -2,7 +2,29 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="ur_arm_gazebo" params="prefix">
<!-- nothing to do here at the moment -->
<gazebo reference="${prefix}shoulder_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}upper_arm_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}forearm_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}wrist_1_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}wrist_3_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}wrist_2_link">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}ee_link">
<selfCollide>true</selfCollide>
</gazebo>
</xacro:macro>
</robot>
......@@ -175,12 +175,8 @@ bool URKinematicsPlugin::initialize(const std::string &robot_description,
ros::NodeHandle private_handle("~");
rdf_loader::RDFLoader rdf_loader(robot_description_);
const boost::shared_ptr<srdf::Model> &srdf = rdf_loader.getSRDF();
#if ROS_VERSION_MINIMUM(1, 13, 0)
const std::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
#else
const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
#endif
const srdf::ModelSharedPtr &srdf = rdf_loader.getSRDF();
const urdf::ModelInterfaceSharedPtr &urdf_model = rdf_loader.getURDF();
if (!urdf_model || !srdf)
{
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment