Public Member Functions | Private Member Functions | Private Attributes
moveit_object_handling::MoveItCollisionMatrixManipulator Class Reference

Provides helper functions to manipulate the MoveIt! Allowed Collision Matrix (ACM). More...

#include <MoveItCollisionMatrixManipulator.h>

List of all members.

Public Member Functions

bool addAllowedMoveItCollision (const std::string &name, const std::vector< std::string > &linkNames)
bool attachMoveItObjectToRobot (const std::string &name, const std::string &link_name, const std::vector< std::string > &allowedTouchLinks)
bool detachMoveItObjectFromRobot (const std::string &name)
bool getCurrentMoveItAllowedCollisionMatrix (moveit_msgs::AllowedCollisionMatrix &matrix)
 MoveItCollisionMatrixManipulator (ros::NodeHandle &nh)
bool setAllowedMoveItCollision (const std::string &name1, const std::string &name2, const bool flag)
bool setAllowedMoveItCollisionMatrix (moveit_msgs::AllowedCollisionMatrix &m)
 ~MoveItCollisionMatrixManipulator ()

Private Member Functions

std::vector< std::string >
::iterator 
ensureExistsInACM (const std::string &name, moveit_msgs::AllowedCollisionMatrix &m, bool initFlag)
void expandMoveItCollisionMatrix (const std::string &name, moveit_msgs::AllowedCollisionMatrix &m, bool default_val)
bool getMoveItScene (octomap_msgs::OctomapWithPose &octomap, std::vector< moveit_msgs::CollisionObject > &collision_objects)
bool hasObject (const std::string &name, const std::vector< moveit_msgs::AttachedCollisionObject > &objs, moveit_msgs::AttachedCollisionObject &o)
bool hasObject (const std::string &name, const std::vector< moveit_msgs::CollisionObject > &objs, moveit_msgs::CollisionObject &o)
bool removeObject (const std::string &name, std::vector< moveit_msgs::CollisionObject > &objs)
bool removeObject (const std::string &name, std::vector< moveit_msgs::AttachedCollisionObject > &objs)

Private Attributes

std::string GET_PLANNING_SCENE_TOPIC
ros::ServiceClient planning_scene_client
ros::Publisher planning_scene_publisher
std::string SET_PLANNING_SCENE_TOPIC

Detailed Description

Provides helper functions to manipulate the MoveIt! Allowed Collision Matrix (ACM).

The ACM saves the expensive collision checking operation by a matrix of flags, where when the flag is 1, it specifies that a collision check between the two objects is not needed (either the two never collide, or have explicitly been allowed to collide). The collision matrix is a symmetric matrix.

The collision matrix is retrieved and set by the ROS MoveIt! planning scene service and topic.

Author:
Jennifer Buehler
Date:
February 2016

Definition at line 33 of file MoveItCollisionMatrixManipulator.h.


Constructor & Destructor Documentation

Definition at line 14 of file MoveItCollisionMatrixManipulator.cpp.

Definition at line 35 of file MoveItCollisionMatrixManipulator.cpp.


Member Function Documentation

bool MoveItCollisionMatrixManipulator::addAllowedMoveItCollision ( const std::string &  name,
const std::vector< std::string > &  linkNames 
)

Allows collisions between collision object name and all links of the robot given in linkNames

Definition at line 96 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::attachMoveItObjectToRobot ( const std::string &  name,
const std::string &  link_name,
const std::vector< std::string > &  allowedTouchLinks 
)

Attaches the object which is known to MoveIt! by name to the link link_name of the robot. The links of the hand which are allowed to touch the object are to be given in allowedTouchLinks.

Returns:
false if MoveIt! planning scene couldn't be reached or if the object is not known as collision object to MoveIt!.

Definition at line 173 of file MoveItCollisionMatrixManipulator.cpp.

Detaches the object which has previously been attached with attachMoveItObjectToRobot() from the robot. Returns false if it wasn't previously attached or MoveIt! planning scene could not be reached.

Definition at line 259 of file MoveItCollisionMatrixManipulator.cpp.

std::vector< std::string >::iterator MoveItCollisionMatrixManipulator::ensureExistsInACM ( const std::string &  name,
moveit_msgs::AllowedCollisionMatrix &  m,
bool  initFlag 
) [private]

Makes sure an entry for this name is added to the collision matrix if it doesn't exist, and then returns the iterator to the ACM.entry_names for it.

Definition at line 125 of file MoveItCollisionMatrixManipulator.cpp.

void MoveItCollisionMatrixManipulator::expandMoveItCollisionMatrix ( const std::string &  name,
moveit_msgs::AllowedCollisionMatrix &  m,
bool  default_val 
) [private]

Expands the collision matrix by appending one row, and one column, and set all fields to default_val.

Definition at line 39 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::getCurrentMoveItAllowedCollisionMatrix ( moveit_msgs::AllowedCollisionMatrix &  matrix)

Gets the current collision matrix of MoveIt!.

Definition at line 55 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::getMoveItScene ( octomap_msgs::OctomapWithPose &  octomap,
std::vector< moveit_msgs::CollisionObject > &  collision_objects 
) [private]

Definition at line 335 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::hasObject ( const std::string &  name,
const std::vector< moveit_msgs::AttachedCollisionObject > &  objs,
moveit_msgs::AttachedCollisionObject &  o 
) [private]

Definition at line 358 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::hasObject ( const std::string &  name,
const std::vector< moveit_msgs::CollisionObject > &  objs,
moveit_msgs::CollisionObject &  o 
) [private]

Definition at line 373 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::removeObject ( const std::string &  name,
std::vector< moveit_msgs::CollisionObject > &  objs 
) [private]

Definition at line 388 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::removeObject ( const std::string &  name,
std::vector< moveit_msgs::AttachedCollisionObject > &  objs 
) [private]

Definition at line 403 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::setAllowedMoveItCollision ( const std::string &  name1,
const std::string &  name2,
const bool  flag 
)

Set the pair <name1, name2> in the collision matrix with the flag. "true" is for allowed collisions (no collision checks needed). If entries for name1 and name2 don't exist, they are added to the collision matrix, and by default are not allowed to collide with any of the other entries (set to "false" for all other objects in ACM).

Definition at line 145 of file MoveItCollisionMatrixManipulator.cpp.

bool MoveItCollisionMatrixManipulator::setAllowedMoveItCollisionMatrix ( moveit_msgs::AllowedCollisionMatrix &  m)

Sets the given collision matrix in MoveIt!.

Definition at line 80 of file MoveItCollisionMatrixManipulator.cpp.


Member Data Documentation

Definition at line 111 of file MoveItCollisionMatrixManipulator.h.

Definition at line 114 of file MoveItCollisionMatrixManipulator.h.

Definition at line 113 of file MoveItCollisionMatrixManipulator.h.

Definition at line 110 of file MoveItCollisionMatrixManipulator.h.


The documentation for this class was generated from the following files:


moveit_object_handling
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:50:51