Helper functions for using image regions of PointCloud2s. More...
Namespaces | |
namespace | cluster_bounding_box_finder |
namespace | cluster_bounding_box_finder_3d |
namespace | convert_functions |
namespace | draw_functions |
namespace | geom |
namespace | image_region_functions |
namespace | msg |
namespace | point_cloud |
namespace | shapes |
Classes | |
class | ActionWrapper |
Wrapper class for SimpleActionClient that checks server availability on first use. More... | |
class | ArmConfigurations |
class | BadParamException |
Thrown when a needed parameter on the parameter server is found but does not have the right type. More... | |
class | CameraConfigurations |
class | CollisionMapException |
Thrown when the grasping pipeline has failed to communicate with the collision map. More... | |
class | ConfigurationLoader |
class | GraspContainer |
class | GraspException |
General base class for all exceptions originating in the grasping pipeline. More... | |
struct | GraspExecutionInfo |
class | GraspMarkerPublisher |
Publishes and keeps track of debug grasp markers. More... | |
class | GraspPerformer |
class | GraspTester |
class | GraspTesterFast |
class | GraspTesterWithApproach |
class | HandDescription |
class | IKTesterFast |
class | IncompatibleRobotStateException |
Thrown if the current robot state prevents any grasp execution. More... | |
class | InterruptRequestedException |
Thrown if the user has requested an interruption. More... | |
class | MechanismException |
Thrown when the grasping pipeline has failed to communicate with or issue commands to the robot. More... | |
class | MechanismInterface |
A collection of ROS service and action clients needed for grasp execution. More... | |
class | MissingParamException |
Thrown when a needed parameter is not found on the parameter server. More... | |
class | MoveArmStuckException |
Thrown if move arm can not plan out of the current arm state. More... | |
class | MultiArmActionWrapper |
A wrapper for multiple instances of a given action, one for each arm in the system. More... | |
class | MultiArmServiceWrapper |
A wrapper for multiple instances of a given service, one for each arm in the system. More... | |
class | MultiArmTopicWrapper |
A wrapper for multiple instances of a topic publisher, one for each arm in the system. More... | |
class | ObjectManipulator |
Oversees the grasping app; bundles together functionality in higher level calls. More... | |
class | ObjectManipulatorNode |
Wraps the Object Manipulator in a ROS API. More... | |
struct | PlaceExecutionInfo |
class | PlacePerformer |
class | PlaceTester |
class | PlaceTesterFast |
class | ReactiveGraspPerformer |
class | ReactivePlacePerformer |
Uses a reactive version of the move from pre-place to place. More... | |
class | ScopedGoalCancel |
Cancels all goals of the client when it goes out of scope. More... | |
class | ServiceNotFoundException |
Thrown when a service or action server was not found. More... | |
class | ServiceWrapper |
Wrapper class for service clients to perform initialization on first use. More... | |
class | StandardGraspPerformer |
Regular grasp performer: moveArm to beginning of approach, execute approach, grasp, execute lift. More... | |
class | StandardPlacePerformer |
class | StandardPlaceTester |
class | UnsafeGraspPerformer |
Uses open-loop Cartesian controllers for all movement. More... | |
class | UnsafeGraspTester |
Does not care about collisions when planning approach and lift. More... | |
Functions | |
ArmConfigurations & | armConfigurations () |
Returns a hand description singleton. | |
CameraConfigurations & | cameraConfigurations () |
Returns a CameraConfigurations singleton. | |
bool | compareLinkPadding (const std::vector< arm_navigation_msgs::LinkPadding > &l1, const std::vector< arm_navigation_msgs::LinkPadding > &l2) |
bool | compareOrderedCollisionOperations (const arm_navigation_msgs::OrderedCollisionOperations &c1, const arm_navigation_msgs::OrderedCollisionOperations &c2) |
arm_navigation_msgs::OrderedCollisionOperations | concat (const arm_navigation_msgs::OrderedCollisionOperations &o1, const arm_navigation_msgs::OrderedCollisionOperations &o2) |
template<class T > | |
std::vector< T > | concat (const std::vector< T > &v1, const std::vector< T > &v2) |
ConfigurationLoader & | configurationLoader () |
Returns a configuration loader singleton. | |
geometry_msgs::Vector3 | doNegate (const geometry_msgs::Vector3 &vec) |
Uses an interpolated IK approach from pregrasp to final grasp. | |
void | drawArrow (ros::Publisher &pub, const shapes::Arrow &shape, const char *ns="arrow", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false) |
void | drawBox (ros::Publisher &pub, const shapes::Box &shape, const char *ns="box", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false) |
void | drawCylinder (ros::Publisher &pub, const shapes::Cylinder &shape, const char *ns="cylinder", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false) |
void | drawMesh (ros::Publisher &pub, const shapes::Mesh &shape, const char *ns="mesh", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false) |
void | drawSphere (ros::Publisher &pub, const shapes::Sphere &shape, const char *ns="sphere", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false) |
double | getJointPosition (std::string name, const arm_navigation_msgs::RobotState &robot_state) |
Finds the state of a given joint in the robot state. | |
HandDescription & | handDescription () |
Returns a hand description singleton. | |
MechanismInterface & | mechInterface () |
Returns a MechanismInterface singleton. | |
void | print_contacts (planning_environment::CollisionModels *cm, planning_models::KinematicState *state) |
void | visualize_grasps (const object_manipulation_msgs::PickupGoal &pickup_goal, const std::vector< manipulation_msgs::Grasp > &grasps, const std::vector< GraspExecutionInfo > &execution_info, ros::Publisher &vis_marker_publisher) |
Variables | |
static const std::string | ATTACHED_COLLISION_TOPIC = "attached_collision_object" |
static const std::string | CARTESIAN_COMMAND_SUFFIX = "/cart/command_pose" |
static const std::string | CARTESIAN_POSTURE_SUFFIX = "/cart/command_posture" |
static const std::string | CHECK_STATE_VALIDITY_NAME = "planning_scene_validity_server/get_state_validity" |
static const std::string | FK_SERVICE_SUFFIX = "/get_fk" |
static const std::string | GET_ROBOT_STATE_NAME = "environment_server/get_robot_state" |
static const std::string | GRASP_STATUS_SUFFIX = "/grasp_status" |
static const std::string | HAND_POSTURE_ACTION_SUFFIX = "/hand_posture_execution" |
static const std::string | IK_QUERY_SERVICE_SUFFIX = "/get_ik_solver_info" |
static const std::string | IK_SERVICE_SUFFIX = "/constraint_aware_ik" |
static const std::string | INTERPOLATED_IK_SERVICE_SUFFIX = "/interpolated_ik" |
static const std::string | INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX = "/interpolated_ik_set_params" |
static const std::string | LIST_CONTROLLERS_SERVICE_NAME = "/list_controllers" |
static const std::string | MARKERS_NAMESPACE = "grasp_markers" |
static const std::string | MARKERS_OUT_NAME = "grasp_execution_markers" |
static const std::string | MOVE_ARM_ACTION_SUFFIX = "/move_arm" |
static const std::string | MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" |
static const std::string | MOVE_ARM_PLANNER_ID = "SBLkConfig1" |
static const std::string | MOVE_ARM_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" |
static const std::string | NORMALIZE_SERVICE_NAME = "trajectory_filter_unnormalizer/filter_trajectory" |
static const double | OBJECT_POSITION_TOLERANCE_X = 0.02 |
static const double | OBJECT_POSITION_TOLERANCE_Y = 0.02 |
static const double | OBJECT_POSITION_TOLERANCE_Z = 0.02 |
static const std::string | PICKUP_ACTION_NAME = "object_manipulator_pickup" |
static const std::string | PLACE_ACTION_NAME = "object_manipulator_place" |
static const std::string | POINT_HEAD_ACTION_TOPIC = "/head_traj_controller/point_head_action" |
static const std::string | REACTIVE_GRASP_ACTION_SUFFIX = "/reactive_grasp" |
static const std::string | REACTIVE_LIFT_ACTION_SUFFIX = "/reactive_lift" |
static const std::string | REACTIVE_PLACE_ACTION_SUFFIX = "/reactive_place" |
static const std::string | RESET_COLLISION_MAP_SERVICE_NAME = "collider_node/reset" |
static const std::string | SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff" |
static const std::string | SWITCH_CONTROLLER_SERVICE_NAME = "/switch_controller" |
static const std::string | TRAJECTORY_ACTION_SUFFIX = "/joint_trajectory" |
Helper functions for using image regions of PointCloud2s.
ArmConfigurations& object_manipulator::armConfigurations | ( | ) | [inline] |
Returns a hand description singleton.
Definition at line 82 of file arm_configurations.h.
CameraConfigurations& object_manipulator::cameraConfigurations | ( | ) | [inline] |
Returns a CameraConfigurations singleton.
Definition at line 115 of file camera_configurations.h.
bool object_manipulator::compareLinkPadding | ( | const std::vector< arm_navigation_msgs::LinkPadding > & | l1, |
const std::vector< arm_navigation_msgs::LinkPadding > & | l2 | ||
) |
Definition at line 168 of file mechanism_interface.cpp.
bool object_manipulator::compareOrderedCollisionOperations | ( | const arm_navigation_msgs::OrderedCollisionOperations & | c1, |
const arm_navigation_msgs::OrderedCollisionOperations & | c2 | ||
) |
Definition at line 153 of file mechanism_interface.cpp.
arm_navigation_msgs::OrderedCollisionOperations object_manipulator::concat | ( | const arm_navigation_msgs::OrderedCollisionOperations & | o1, |
const arm_navigation_msgs::OrderedCollisionOperations & | o2 | ||
) |
Definition at line 41 of file vector_tools.cpp.
std::vector<T> object_manipulator::concat | ( | const std::vector< T > & | v1, |
const std::vector< T > & | v2 | ||
) | [inline] |
Definition at line 42 of file vector_tools.h.
ConfigurationLoader& object_manipulator::configurationLoader | ( | ) | [inline] |
Returns a configuration loader singleton.
Definition at line 111 of file configuration_loader.h.
geometry_msgs::Vector3 object_manipulator::doNegate | ( | const geometry_msgs::Vector3 & | vec | ) | [inline] |
Uses an interpolated IK approach from pregrasp to final grasp.
Checks a batch of IK queries at once.
Initial check consists of IK for the pre-grasp, followed by generation of an interpolated IK path from pre-grasp to grasp. This is then followed by computation of an interpolated IK path from grasp to lift.
Execution consists of using move arm to go to the pre-grasp, then execution of the interpolated IK paths for grasp. Lift is executed separately, called from the higher level executor.
Note that we do not use the pre-grasp from the database directly; rather, the pre-grasp is obtained by backing up the grasp by a pre-defined amount. This allows us more flexibility in choosing the pre-grasp. However, we can no longer always assume the pre-grasp is collision free, which we could if we used the pre-grasp from the database directly.
In the most recent database version, the pre-grasp was obtained by backing up 10 cm, so we know at least that that is not colliding with the object.
Definition at line 66 of file grasp_tester_fast.h.
void object_manipulator::drawArrow | ( | ros::Publisher & | pub, |
const shapes::Arrow & | shape, | ||
const char * | ns = "arrow" , |
||
int | id = 0 , |
||
const ros::Duration | lifetime = ros::Duration() , |
||
const std_msgs::ColorRGBA | color = msg::createColorMsg(0.5, 0.5, 0.5, 0.5) , |
||
bool | destroy = false , |
||
bool | frame_locked = false |
||
) |
Definition at line 95 of file shape_tools.cpp.
void object_manipulator::drawBox | ( | ros::Publisher & | pub, |
const shapes::Box & | shape, | ||
const char * | ns = "box" , |
||
int | id = 0 , |
||
const ros::Duration | lifetime = ros::Duration() , |
||
const std_msgs::ColorRGBA | color = msg::createColorMsg(0.5, 0.5, 0.5, 0.5) , |
||
bool | destroy = false , |
||
bool | frame_locked = false |
||
) |
Definition at line 61 of file shape_tools.cpp.
void object_manipulator::drawCylinder | ( | ros::Publisher & | pub, |
const shapes::Cylinder & | shape, | ||
const char * | ns = "cylinder" , |
||
int | id = 0 , |
||
const ros::Duration | lifetime = ros::Duration() , |
||
const std_msgs::ColorRGBA | color = msg::createColorMsg(0.5, 0.5, 0.5, 0.5) , |
||
bool | destroy = false , |
||
bool | frame_locked = false |
||
) |
Definition at line 44 of file shape_tools.cpp.
void object_manipulator::drawMesh | ( | ros::Publisher & | pub, |
const shapes::Mesh & | shape, | ||
const char * | ns = "mesh" , |
||
int | id = 0 , |
||
const ros::Duration | lifetime = ros::Duration() , |
||
const std_msgs::ColorRGBA | color = msg::createColorMsg(0.5, 0.5, 0.5, 0.5) , |
||
bool | destroy = false , |
||
bool | frame_locked = false |
||
) |
Definition at line 112 of file shape_tools.cpp.
void object_manipulator::drawSphere | ( | ros::Publisher & | pub, |
const shapes::Sphere & | shape, | ||
const char * | ns = "sphere" , |
||
int | id = 0 , |
||
const ros::Duration | lifetime = ros::Duration() , |
||
const std_msgs::ColorRGBA | color = msg::createColorMsg(0.5, 0.5, 0.5, 0.5) , |
||
bool | destroy = false , |
||
bool | frame_locked = false |
||
) |
Definition at line 78 of file shape_tools.cpp.
double object_manipulator::getJointPosition | ( | std::string | name, |
const arm_navigation_msgs::RobotState & | robot_state | ||
) |
Finds the state of a given joint in the robot state.
Definition at line 449 of file mechanism_interface.cpp.
HandDescription& object_manipulator::handDescription | ( | ) | [inline] |
Returns a hand description singleton.
Definition at line 130 of file hand_description.h.
MechanismInterface& object_manipulator::mechInterface | ( | ) | [inline] |
Returns a MechanismInterface singleton.
Due to problems with waitForServer, it is not recommended to use multiple instances of the MechanismInterface in the same node. This function provides a singleton.
CAREFUL WITH MULTI-THREADED CODE!!!
Definition at line 541 of file mechanism_interface.h.
void object_manipulator::print_contacts | ( | planning_environment::CollisionModels * | cm, |
planning_models::KinematicState * | state | ||
) |
Definition at line 51 of file grasp_tester_fast.cpp.
void object_manipulator::visualize_grasps | ( | const object_manipulation_msgs::PickupGoal & | pickup_goal, |
const std::vector< manipulation_msgs::Grasp > & | grasps, | ||
const std::vector< GraspExecutionInfo > & | execution_info, | ||
ros::Publisher & | vis_marker_publisher | ||
) |
Definition at line 66 of file grasp_tester_fast.cpp.
const std::string object_manipulator::ATTACHED_COLLISION_TOPIC = "attached_collision_object" [static] |
Definition at line 75 of file mechanism_interface.cpp.
const std::string object_manipulator::CARTESIAN_COMMAND_SUFFIX = "/cart/command_pose" [static] |
Definition at line 67 of file mechanism_interface.cpp.
const std::string object_manipulator::CARTESIAN_POSTURE_SUFFIX = "/cart/command_posture" [static] |
Definition at line 68 of file mechanism_interface.cpp.
const std::string object_manipulator::CHECK_STATE_VALIDITY_NAME = "planning_scene_validity_server/get_state_validity" [static] |
Definition at line 53 of file mechanism_interface.cpp.
const std::string object_manipulator::FK_SERVICE_SUFFIX = "/get_fk" [static] |
Definition at line 46 of file mechanism_interface.cpp.
const std::string object_manipulator::GET_ROBOT_STATE_NAME = "environment_server/get_robot_state" [static] |
Definition at line 54 of file mechanism_interface.cpp.
const std::string object_manipulator::GRASP_STATUS_SUFFIX = "/grasp_status" [static] |
Definition at line 50 of file mechanism_interface.cpp.
const std::string object_manipulator::HAND_POSTURE_ACTION_SUFFIX = "/hand_posture_execution" [static] |
Definition at line 63 of file mechanism_interface.cpp.
const std::string object_manipulator::IK_QUERY_SERVICE_SUFFIX = "/get_ik_solver_info" [static] |
Definition at line 49 of file mechanism_interface.cpp.
const std::string object_manipulator::IK_SERVICE_SUFFIX = "/constraint_aware_ik" [static] |
Definition at line 45 of file mechanism_interface.cpp.
const std::string object_manipulator::INTERPOLATED_IK_SERVICE_SUFFIX = "/interpolated_ik" [static] |
Definition at line 47 of file mechanism_interface.cpp.
const std::string object_manipulator::INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX = "/interpolated_ik_set_params" [static] |
Definition at line 48 of file mechanism_interface.cpp.
const std::string object_manipulator::LIST_CONTROLLERS_SERVICE_NAME = "/list_controllers" [static] |
Definition at line 66 of file mechanism_interface.cpp.
const std::string object_manipulator::MARKERS_NAMESPACE = "grasp_markers" [static] |
Definition at line 42 of file grasp_marker_publisher.cpp.
const std::string object_manipulator::MARKERS_OUT_NAME = "grasp_execution_markers" [static] |
Definition at line 41 of file grasp_marker_publisher.cpp.
const std::string object_manipulator::MOVE_ARM_ACTION_SUFFIX = "/move_arm" [static] |
Definition at line 61 of file mechanism_interface.cpp.
const std::string object_manipulator::MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" [static] |
Definition at line 73 of file mechanism_interface.cpp.
const std::string object_manipulator::MOVE_ARM_PLANNER_ID = "SBLkConfig1" [static] |
Definition at line 71 of file mechanism_interface.cpp.
const std::string object_manipulator::MOVE_ARM_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" [static] |
Definition at line 72 of file mechanism_interface.cpp.
const std::string object_manipulator::NORMALIZE_SERVICE_NAME = "trajectory_filter_unnormalizer/filter_trajectory" [static] |
Definition at line 55 of file mechanism_interface.cpp.
const double object_manipulator::OBJECT_POSITION_TOLERANCE_X = 0.02 [static] |
Definition at line 79 of file mechanism_interface.cpp.
const double object_manipulator::OBJECT_POSITION_TOLERANCE_Y = 0.02 [static] |
Definition at line 80 of file mechanism_interface.cpp.
const double object_manipulator::OBJECT_POSITION_TOLERANCE_Z = 0.02 [static] |
Definition at line 81 of file mechanism_interface.cpp.
const std::string object_manipulator::PICKUP_ACTION_NAME = "object_manipulator_pickup" [static] |
Definition at line 47 of file object_manipulator_node.cpp.
const std::string object_manipulator::PLACE_ACTION_NAME = "object_manipulator_place" [static] |
Definition at line 48 of file object_manipulator_node.cpp.
const std::string object_manipulator::POINT_HEAD_ACTION_TOPIC = "/head_traj_controller/point_head_action" [static] |
Definition at line 77 of file mechanism_interface.cpp.
const std::string object_manipulator::REACTIVE_GRASP_ACTION_SUFFIX = "/reactive_grasp" [static] |
Definition at line 58 of file mechanism_interface.cpp.
const std::string object_manipulator::REACTIVE_LIFT_ACTION_SUFFIX = "/reactive_lift" [static] |
Definition at line 59 of file mechanism_interface.cpp.
const std::string object_manipulator::REACTIVE_PLACE_ACTION_SUFFIX = "/reactive_place" [static] |
Definition at line 60 of file mechanism_interface.cpp.
const std::string object_manipulator::RESET_COLLISION_MAP_SERVICE_NAME = "collider_node/reset" [static] |
Definition at line 56 of file mechanism_interface.cpp.
const std::string object_manipulator::SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff" [static] |
Definition at line 52 of file mechanism_interface.cpp.
const std::string object_manipulator::SWITCH_CONTROLLER_SERVICE_NAME = "/switch_controller" [static] |
Definition at line 65 of file mechanism_interface.cpp.
const std::string object_manipulator::TRAJECTORY_ACTION_SUFFIX = "/joint_trajectory" [static] |
Definition at line 62 of file mechanism_interface.cpp.