Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini committed Mar 11, 2022
2 parents 44ff32b + ab42a1d commit a589e54
Show file tree
Hide file tree
Showing 87 changed files with 495 additions and 530 deletions.
8 changes: 6 additions & 2 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@ jobs:
IKFAST_TEST: true
CLANG_TIDY: pedantic
env:
CXXFLAGS: "-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-deprecated-copy"
CXXFLAGS: >-
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
DOCKER_IMAGE: ghcr.io/ros-planning/moveit2:${{ matrix.env.IMAGE }}
UPSTREAM_WORKSPACE: moveit2.repos $(f="moveit2_$(sed 's/-.*$//' <<< "${{ matrix.env.IMAGE }}").repos"; test -r $f && echo $f)
Expand All @@ -39,12 +40,15 @@ jobs:
BEFORE_BUILD_UPSTREAM_WORKSPACE: ccache -z
AFTER_BUILD_TARGET_WORKSPACE: ccache -s
# Changing linker to lld as ld has a behavior where it takes a long time to finish
# Compile CCOV with Debug. Enable -Werror (except CLANG_TIDY=pedantic, which makes the clang-tidy step fail on warnings)
TARGET_CMAKE_ARGS: >
-DCMAKE_EXE_LINKER_FLAGS=-fuse-ld=lld
-DCMAKE_SHARED_LINKER_FLAGS=-fuse-ld=lld
-DCMAKE_MODULE_LINKER_FLAGS=-fuse-ld=lld
-DCMAKE_BUILD_TYPE=${{ matrix.env.CCOV && 'Debug' || 'Release'}}
-DCMAKE_CXX_FLAGS="${{ matrix.env.CLANG_TIDY != 'pedantic' && '-Werror ' || '' }}${{ matrix.env.CCOV && ' --coverage -O2 -fno-omit-frame-pointer'}}"
-DCMAKE_CXX_FLAGS="${{ matrix.env.CLANG_TIDY != 'pedantic' && '-Werror ' || '' }}$CXXFLAGS${{ matrix.env.CCOV && ' --coverage -O2 -fno-omit-frame-pointer'}}"
UPSTREAM_CMAKE_ARGS: "-DCMAKE_CXX_FLAGS=''"
DOWNSTREAM_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-Wall -Wextra"
CCACHE_DIR: ${{ github.workspace }}/.ccache
BASEDIR: ${{ github.workspace }}/.work
CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }}
Expand Down
5 changes: 3 additions & 2 deletions moveit/scripts/create_readme_table.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-
# Usage: python moveit/moveit/scripts/create_readme_table.py > /tmp/table.md
# First update supported_distro_ubuntu_dict below!

# Copyright 2021 PickNik Inc.
#
Expand Down Expand Up @@ -77,7 +79,7 @@ def create_line(package, ros_ubuntu_dict):
"U": ubuntu[0].upper(),
"ubuntu": ubuntu.lower(),
"package": package,
"base_url": "http://build.ros.org",
"base_url": "https://build.ros.org",
}
for target in ["src", "bin"]:
define_urls(target, params)
Expand All @@ -102,7 +104,6 @@ def create_moveit_buildfarm_table():
# remove {"indigo":"trusty"} and add {"noetic":"fbuntu"} with "fbuntu"
# being whatever the 20.04 distro is named
supported_distro_ubuntu_dict = {
"kinetic": "xenial",
"melodic": "bionic",
"noetic": "focal",
}
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan, E. Gil Jones */

#include <moveit/collision_detection/collision_matrix.h>
#include <boost/bind.hpp>
#include <functional>
#include <iomanip>
#include "rclcpp/rclcpp.hpp"

Expand Down Expand Up @@ -280,7 +280,7 @@ bool AllowedCollisionMatrix::getAllowedCollision(const std::string& name1, const
else if (!found1 && found2)
fn = fn2;
else if (found1 && found2)
fn = boost::bind(&andDecideContact, fn1, fn2, _1);
fn = std::bind(&andDecideContact, fn1, fn2, std::placeholders::_1);
else
return false;
return true;
Expand Down
14 changes: 9 additions & 5 deletions moveit_core/collision_detection/src/world_diff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley, Ioan Sucan */

#include <moveit/collision_detection/world_diff.h>
#include <boost/bind.hpp>
#include <functional>

namespace collision_detection
{
Expand All @@ -52,7 +52,8 @@ WorldDiff::WorldDiff()

WorldDiff::WorldDiff(const WorldPtr& world) : world_(world)
{
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}

WorldDiff::WorldDiff(WorldDiff& other)
Expand All @@ -63,7 +64,8 @@ WorldDiff::WorldDiff(WorldDiff& other)
changes_ = other.changes_;

WorldWeakPtr(world).swap(world_);
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}
}

Expand All @@ -87,7 +89,8 @@ void WorldDiff::reset(const WorldPtr& world)
old_world->removeObserver(observer_handle_);

WorldWeakPtr(world).swap(world_);
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}

void WorldDiff::setWorld(const WorldPtr& world)
Expand All @@ -101,7 +104,8 @@ void WorldDiff::setWorld(const WorldPtr& world)

WorldWeakPtr(world).swap(world_);

observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
world->notifyObserverAllObjects(observer_handle_, World::CREATE | World::ADD_SHAPE);
}

Expand Down
10 changes: 5 additions & 5 deletions moveit_core/collision_detection/test/test_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <gtest/gtest.h>
#include <moveit/collision_detection/world.h>
#include <geometric_shapes/shapes.h>
#include <boost/bind.hpp>
#include <functional>

TEST(World, AddRemoveShape)
{
Expand Down Expand Up @@ -236,7 +236,7 @@ TEST(World, TrackChanges)

TestAction ta;
collision_detection::World::ObserverHandle observer_ta;
observer_ta = world.addObserver(boost::bind(TrackChangesNotify, &ta, _1, _2));
observer_ta = world.addObserver(std::bind(TrackChangesNotify, &ta, std::placeholders::_1, std::placeholders::_2));

// Create some shapes
shapes::ShapePtr ball(new shapes::Sphere(1.0));
Expand Down Expand Up @@ -267,7 +267,7 @@ TEST(World, TrackChanges)

TestAction ta2;
collision_detection::World::ObserverHandle observer_ta2;
observer_ta2 = world.addObserver(boost::bind(TrackChangesNotify, &ta2, _1, _2));
observer_ta2 = world.addObserver(std::bind(TrackChangesNotify, &ta2, std::placeholders::_1, std::placeholders::_2));

world.addToObject("obj2", cyl, Eigen::Isometry3d::Identity());

Expand Down Expand Up @@ -305,7 +305,7 @@ TEST(World, TrackChanges)

TestAction ta3;
collision_detection::World::ObserverHandle observer_ta3;
observer_ta3 = world.addObserver(boost::bind(TrackChangesNotify, &ta3, _1, _2));
observer_ta3 = world.addObserver(std::bind(TrackChangesNotify, &ta3, std::placeholders::_1, std::placeholders::_2));

bool rm_good = world.removeShapeFromObject("obj2", cyl);
EXPECT_TRUE(rm_good);
Expand Down Expand Up @@ -371,7 +371,7 @@ TEST(World, ObjectPoseAndSubframes)

TestAction ta;
collision_detection::World::ObserverHandle observer_ta;
observer_ta = world.addObserver(boost::bind(TrackChangesNotify, &ta, _1, _2));
observer_ta = world.addObserver(std::bind(TrackChangesNotify, &ta, std::placeholders::_1, std::placeholders::_2));

// Create shapes
shapes::ShapePtr ball(new shapes::Sphere(1.0));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include <moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h>
#include <moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h>
#include <boost/bind.hpp>
#include <functional>
#include <bullet/btBulletCollisionCommon.h>

namespace collision_detection
Expand All @@ -51,7 +51,8 @@ CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& m
: CollisionEnv(model, padding, scale)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
{
Expand All @@ -64,7 +65,8 @@ CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& m
: CollisionEnv(model, world, padding, scale)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
{
Expand All @@ -78,7 +80,8 @@ CollisionEnvBullet::CollisionEnvBullet(const CollisionEnvBullet& other, const Wo
: CollisionEnv(other, world)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : other.robot_model_->getURDF()->links_)
{
Expand Down Expand Up @@ -301,7 +304,8 @@ void CollisionEnvBullet::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
12 changes: 8 additions & 4 deletions moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model,
manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world, double padding,
Expand Down Expand Up @@ -142,7 +143,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model,
manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}

Expand All @@ -164,7 +166,8 @@ CollisionEnvFCL::CollisionEnvFCL(const CollisionEnvFCL& other, const WorldPtr& w
// manager_->update();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

void CollisionEnvFCL::getAttachedBodyObjects(const moveit::core::AttachedBody* ab,
Expand Down Expand Up @@ -405,7 +408,8 @@ void CollisionEnvFCL::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <moveit/collision_distance_field/collision_common_distance_field.h>
#include <moveit/distance_field/propagation_distance_field.h>
#include <moveit/collision_distance_field/collision_detector_allocator_distance_field.h>
#include <boost/bind.hpp>
#include <functional>
#include <memory>
#include <utility>

Expand All @@ -71,7 +71,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

CollisionEnvDistanceField::CollisionEnvDistanceField(
Expand All @@ -87,7 +88,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}
Expand All @@ -110,7 +112,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(const CollisionEnvDistanceF
planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}

Expand Down Expand Up @@ -1689,7 +1692,8 @@ void CollisionEnvDistanceField::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include <moveit/constraint_samplers/default_constraint_samplers.h>
#include <cassert>
#include <boost/bind.hpp>
#include <functional>

namespace constraint_samplers
{
Expand Down Expand Up @@ -561,8 +561,8 @@ bool IKConstraintSampler::sampleHelper(moveit::core::RobotState& state, const mo

kinematics::KinematicsBase::IKCallbackFn adapted_ik_validity_callback;
if (group_state_validity_callback_)
adapted_ik_validity_callback =
boost::bind(&samplingIkCallbackFnAdapter, &state, jmg_, group_state_validity_callback_, _1, _2, _3);
adapted_ik_validity_callback = std::bind(&samplingIkCallbackFnAdapter, &state, jmg_, group_state_validity_callback_,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);

for (unsigned int a = 0; a < max_attempts; ++a)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
#include <gtest/gtest.h>
#include <urdf_parser/urdf_parser.h>
#include <fstream>
#include <boost/bind.hpp>
#include <functional>

#include "pr2_arm_kinematics_plugin.h"

Expand Down Expand Up @@ -83,8 +83,8 @@ class LoadPlanningModelsPr2 : public testing::Test
pr2_kinematics_plugin_left_arm_->initialize(node_, *robot_model_, "left_arm", "torso_lift_link",
{ "l_wrist_roll_link" }, .01);

func_right_arm_ = boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverRightArm, this, _1);
func_left_arm_ = boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverLeftArm, this, _1);
func_right_arm_ = std::bind(&LoadPlanningModelsPr2::getKinematicsSolverRightArm, this, std::placeholders::_1);
func_left_arm_ = std::bind(&LoadPlanningModelsPr2::getKinematicsSolverLeftArm, this, std::placeholders::_1);

std::map<std::string, moveit::core::SolverAllocatorFn> allocators;
allocators["right_arm"] = func_right_arm_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#else
#include <tf2_eigen/tf2_eigen.h>
#endif
#include <boost/bind.hpp>
#include <functional>
#include <limits>
#include <memory>
#include <typeinfo>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan */

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <boost/bind.hpp>
#include <functional>
#include <algorithm>
#include "rclcpp/rclcpp.hpp"

Expand Down Expand Up @@ -66,8 +66,9 @@ bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManag
planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index) const
{
return adaptAndPlan(boost::bind(&callPlannerInterfaceSolve, planner.get(), _1, _2, _3), planning_scene, req, res,
added_path_index);
return adaptAndPlan(std::bind(&callPlannerInterfaceSolve, planner.get(), std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
planning_scene, req, res, added_path_index);
}

bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
Expand Down Expand Up @@ -148,10 +149,12 @@ bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::Planner

// if there are adapters, construct a function pointer for each, in order,
// so that in the end we have a nested sequence of function pointers that call the adapters in the correct order.
PlanningRequestAdapter::PlannerFn fn = boost::bind(&callAdapter1, adapters_.back().get(), planner, _1, _2, _3,
boost::ref(added_path_index_each.back()));
PlanningRequestAdapter::PlannerFn fn =
std::bind(&callAdapter1, adapters_.back().get(), planner, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3, boost::ref(added_path_index_each.back()));
for (int i = adapters_.size() - 2; i >= 0; --i)
fn = boost::bind(&callAdapter2, adapters_[i].get(), fn, _1, _2, _3, boost::ref(added_path_index_each[i]));
fn = std::bind(&callAdapter2, adapters_[i].get(), fn, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3, boost::ref(added_path_index_each[i]));
bool result = fn(planning_scene, req, res);
added_path_index.clear();

Expand Down
Loading

0 comments on commit a589e54

Please sign in to comment.