Skip to content

Commit

Permalink
Merge pull request #209 from fmessmer/release_fixes
Browse files Browse the repository at this point in the history
[Melodic] release fixes
  • Loading branch information
fmessmer authored Aug 9, 2019
2 parents 4fde4f4 + c130441 commit 6d1a917
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 7 deletions.
2 changes: 0 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@ env:
global:
- ROS_REPO=ros
matrix:
- ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=file
- ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=debian
- ROS_DISTRO=melodic UPSTREAM_WORKSPACE=file
- ROS_DISTRO=melodic UPSTREAM_WORKSPACE=debian
install:
Expand Down
10 changes: 5 additions & 5 deletions cob_obstacle_distance/src/link_to_collision.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,15 +190,15 @@ void LinkToCollision::createSpecificMarkerShape(const std::string& link_of_inter
test_col.a = 0.0;
test_col.r = 0.0;

PtrMesh_t mesh = boost::static_pointer_cast<urdf::Mesh>(geometry);
PtrMesh_t mesh = std::static_pointer_cast<urdf::Mesh>(geometry);
segment_of_interest_marker_shape.reset(new MarkerShape<BVH_RSS_t>(this->root_frame_id_,
mesh->filename,
pose,
col));
}
else if (urdf::Geometry::BOX == geometry->type)
{
PtrBox_t urdf_box = boost::static_pointer_cast<urdf::Box>(geometry);
PtrBox_t urdf_box = std::static_pointer_cast<urdf::Box>(geometry);
fcl::Box b(urdf_box->dim.x,
urdf_box->dim.y,
urdf_box->dim.z);
Expand All @@ -216,7 +216,7 @@ void LinkToCollision::createSpecificMarkerShape(const std::string& link_of_inter
test_col.a = 1.0;
test_col.b = 1.0;

PtrSphere_t urdf_sphere = boost::static_pointer_cast<urdf::Sphere>(geometry);
PtrSphere_t urdf_sphere = std::static_pointer_cast<urdf::Sphere>(geometry);
fcl::Sphere s(urdf_sphere->radius);
segment_of_interest_marker_shape.reset(new MarkerShape<fcl::Sphere>(this->root_frame_id_, s, pose, test_col));
}
Expand All @@ -226,7 +226,7 @@ void LinkToCollision::createSpecificMarkerShape(const std::string& link_of_inter
test_col.a = 1.0;
test_col.g = 1.0;

PtrCylinder_t urdf_cyl = boost::static_pointer_cast<urdf::Cylinder>(geometry);
PtrCylinder_t urdf_cyl = std::static_pointer_cast<urdf::Cylinder>(geometry);
fcl::Cylinder c(urdf_cyl->radius, urdf_cyl->length);
segment_of_interest_marker_shape.reset(new MarkerShape<fcl::Cylinder>(this->root_frame_id_, c, pose, test_col));
}
Expand Down Expand Up @@ -276,7 +276,7 @@ bool LinkToCollision::getMarkerShapeFromType(const uint32_t& shape_type,
NULL != link->collision->geometry &&
link->collision->geometry->type == urdf::Geometry::MESH)
{
PtrMesh_t mesh = boost::static_pointer_cast<urdf::Mesh>(link->collision->geometry);
PtrMesh_t mesh = std::static_pointer_cast<urdf::Mesh>(link->collision->geometry);
mesh_resource = mesh->filename;
}
else
Expand Down

0 comments on commit 6d1a917

Please sign in to comment.