Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini committed Nov 29, 2021
2 parents 97ebea3 + 865c261 commit 77075f5
Show file tree
Hide file tree
Showing 42 changed files with 408 additions and 336 deletions.
1 change: 1 addition & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ API changes in MoveIt releases
- The joint states of `passive` joints must be published in ROS and the CurrentStateMonitor will now wait for them as well. Their semantics dictate that they cannot be actively controlled, but they must be known to use the full robot state in collision checks. (https://github.com/ros-planning/moveit/pull/2663)
- Removed deprecated header `moveit/macros/deprecation.h`. Use `[[deprecated]]` instead.
- All uses of `MOVEIT_CLASS_FORWARD` et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase).
- In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. `<ns>/move_group/display_planned_path` instead of `/move_group/display_planned_path`).

## ROS Melodic

Expand Down
2 changes: 1 addition & 1 deletion moveit_commander/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_commander</name>
<version>1.1.5</version>
<version>1.1.6</version>
<description>Python interfaces to MoveIt</description>
<maintainer email="[email protected]">Michael Görner</maintainer>
<maintainer email="[email protected]">Robert Haschke</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -409,7 +409,7 @@ inline btScalar addDiscreteSingleResult(btManifoldPoint& cp, const btCollisionOb
contact.nearest_points[1] = convertBtToEigen(cp.m_positionWorldOnB);

contact.body_type_1 = cd0->getTypeID();
contact.body_type_2 = cd0->getTypeID();
contact.body_type_2 = cd1->getTypeID();

if (!processResult(collisions, contact, pc, found))
{
Expand Down Expand Up @@ -442,7 +442,7 @@ inline btScalar addCastSingleResult(btManifoldPoint& cp, const btCollisionObject
contact.pos = convertBtToEigen(cp.m_positionWorldOnA);

contact.body_type_1 = cd0->getTypeID();
contact.body_type_2 = cd0->getTypeID();
contact.body_type_2 = cd1->getTypeID();

collision_detection::Contact* col = processResult(collisions, contact, pc, found);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -313,6 +313,21 @@ TEST_F(BulletCollisionDetectionTester, ContinuousCollisionWorld)
cenv_->checkRobotCollision(req, res, state1, state2, *acm_);
ASSERT_TRUE(res.collision);
ASSERT_EQ(res.contact_count, 4u);
// test contact types
for (auto& contact_pair : res.contacts)
{
for (collision_detection::Contact& contact : contact_pair.second)
{
collision_detection::BodyType contact_type1 = contact.body_name_1 == "box" ?
collision_detection::BodyType::WORLD_OBJECT :
collision_detection::BodyType::ROBOT_LINK;
collision_detection::BodyType contact_type2 = contact.body_name_2 == "box" ?
collision_detection::BodyType::WORLD_OBJECT :
collision_detection::BodyType::ROBOT_LINK;
ASSERT_EQ(contact.body_type_1, contact_type1);
ASSERT_EQ(contact.body_type_2, contact_type2);
}
}
res.clear();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1225,6 +1225,15 @@ class RobotState
/** \brief Set the joints in \e group to the position \e name defined in the SRDF */
bool setToDefaultValues(const JointModelGroup* group, const std::string& name);

bool setToDefaultValues(const std::string& group_name, const std::string& state_name)
{
const JointModelGroup* jmg = getJointModelGroup(group_name);
if (jmg)
return setToDefaultValues(jmg, state_name);
else
return false;
}

/** \brief Set all joints to random values. Values will be within default bounds. */
void setToRandomPositions();

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<name>moveit_planners_chomp</name>
<description>The interface for using CHOMP within MoveIt</description>

<version>1.1.5</version>
<version>1.1.6</version>
<author email="[email protected]">Gil Jones</author>

<maintainer email="[email protected]">Chittaranjan Srinivas Swaminathan</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_motion_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<name>chomp_motion_planner</name>
<description>chomp_motion_planner</description>

<version>1.1.5</version>
<version>1.1.6</version>
<author email="[email protected]">Gil Jones</author>
<author email="[email protected]">Mrinal Kalakrishnan</author>

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_optimizer_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<name>moveit_chomp_optimizer_adapter</name>
<description>MoveIt planning request adapter utilizing chomp for solution optimization</description>

<version>1.1.5</version>
<version>1.1.6</version>
<author email="[email protected]">Raghavender Sahdev</author>
<maintainer email="[email protected]">Raghavender Sahdev</maintainer>
<maintainer email="[email protected]">MoveIt Release Team</maintainer>
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading

0 comments on commit 77075f5

Please sign in to comment.