diff --git a/dependencies.rosinstall b/dependencies.rosinstall index 91326dea0..644766f7e 100644 --- a/dependencies.rosinstall +++ b/dependencies.rosinstall @@ -5,15 +5,15 @@ - git: local-name: tesseract uri: https://github.com/tesseract-robotics/tesseract.git - version: 80d60cef50e7bebd957de627e9a987534f0c678a + version: 0.7.0 - git: local-name: trajopt uri: https://github.com/tesseract-robotics/trajopt.git - version: c02b1dfb1ad49c688856b482092700439f57c867 + version: 0.2.0 - git: local-name: tesseract_planning uri: https://github.com/tesseract-robotics/tesseract_planning.git - version: b8a95bfbd2efc46eb2dda69f108e2bac822310cf + version: 0.7.0 - git: local-name: descartes_light uri: https://github.com/swri-robotics/descartes_light.git diff --git a/dependencies_with_ext.rosinstall b/dependencies_with_ext.rosinstall index 3184efe07..0e17563ce 100644 --- a/dependencies_with_ext.rosinstall +++ b/dependencies_with_ext.rosinstall @@ -9,15 +9,15 @@ - git: local-name: tesseract uri: https://github.com/tesseract-robotics/tesseract.git - version: 80d60cef50e7bebd957de627e9a987534f0c678a + version: 0.7.0 - git: local-name: trajopt uri: https://github.com/tesseract-robotics/trajopt_ros.git - version: c02b1dfb1ad49c688856b482092700439f57c867 + version: 0.2.0 - git: local-name: tesseract_planning uri: https://github.com/tesseract-robotics/tesseract_planning.git - version: b8a95bfbd2efc46eb2dda69f108e2bac822310cf + version: 0.7.0 - git: local-name: descartes_light uri: https://github.com/swri-robotics/descartes_light.git diff --git a/tesseract_ros_examples/src/glass_upright_example.cpp b/tesseract_ros_examples/src/glass_upright_example.cpp index de80d64cf..82b82d9c2 100644 --- a/tesseract_ros_examples/src/glass_upright_example.cpp +++ b/tesseract_ros_examples/src/glass_upright_example.cpp @@ -195,10 +195,11 @@ bool GlassUprightExample::run() { auto composite_profile = std::make_shared(); composite_profile->collision_cost_config->type = tesseract_collision::CollisionEvaluatorType::LVS_DISCRETE; - composite_profile->collision_cost_config->contact_manager_config.collision_margin_data.setDefaultCollisionMargin(0.01); + composite_profile->collision_cost_config->contact_manager_config = tesseract_collision::ContactManagerConfig(0.01); composite_profile->collision_cost_config->collision_margin_buffer = 0.01; composite_profile->collision_constraint_config->type = tesseract_collision::CollisionEvaluatorType::LVS_DISCRETE; - composite_profile->collision_constraint_config->contact_manager_config.collision_margin_data.setDefaultCollisionMargin(0.01); + composite_profile->collision_constraint_config->contact_manager_config = + tesseract_collision::ContactManagerConfig(0.01); composite_profile->collision_constraint_config->collision_margin_buffer = 0.01; composite_profile->smooth_velocities = true; composite_profile->smooth_accelerations = false; diff --git a/tesseract_rosutils/package.xml b/tesseract_rosutils/package.xml index 09d22d0f6..ed2113176 100644 --- a/tesseract_rosutils/package.xml +++ b/tesseract_rosutils/package.xml @@ -30,6 +30,7 @@ roscpp roslib std_msgs + visualization_msgs tesseract_support