#include "object_manipulator/tools/mechanism_interface.h"
#include "object_manipulator/tools/hand_description.h"
#include "object_manipulator/tools/exceptions.h"
Go to the source code of this file.
Namespaces | |
namespace | object_manipulator |
Helper functions for using image regions of PointCloud2s. | |
Functions | |
bool | object_manipulator::compareLinkPadding (const std::vector< arm_navigation_msgs::LinkPadding > &l1, const std::vector< arm_navigation_msgs::LinkPadding > &l2) |
bool | object_manipulator::compareOrderedCollisionOperations (const arm_navigation_msgs::OrderedCollisionOperations &c1, const arm_navigation_msgs::OrderedCollisionOperations &c2) |
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. | |
Variables | |
static const std::string | object_manipulator::ATTACHED_COLLISION_TOPIC = "attached_collision_object" |
static const std::string | object_manipulator::CARTESIAN_COMMAND_SUFFIX = "/cart/command_pose" |
static const std::string | object_manipulator::CARTESIAN_POSTURE_SUFFIX = "/cart/command_posture" |
static const std::string | object_manipulator::CHECK_STATE_VALIDITY_NAME = "planning_scene_validity_server/get_state_validity" |
static const std::string | object_manipulator::FK_SERVICE_SUFFIX = "/get_fk" |
static const std::string | object_manipulator::GET_ROBOT_STATE_NAME = "environment_server/get_robot_state" |
static const std::string | object_manipulator::GRASP_STATUS_SUFFIX = "/grasp_status" |
static const std::string | object_manipulator::HAND_POSTURE_ACTION_SUFFIX = "/hand_posture_execution" |
static const std::string | object_manipulator::IK_QUERY_SERVICE_SUFFIX = "/get_ik_solver_info" |
static const std::string | object_manipulator::IK_SERVICE_SUFFIX = "/constraint_aware_ik" |
static const std::string | object_manipulator::INTERPOLATED_IK_SERVICE_SUFFIX = "/interpolated_ik" |
static const std::string | object_manipulator::INTERPOLATED_IK_SET_PARAMS_SERVICE_SUFFIX = "/interpolated_ik_set_params" |
static const std::string | object_manipulator::LIST_CONTROLLERS_SERVICE_NAME = "/list_controllers" |
static const std::string | object_manipulator::MOVE_ARM_ACTION_SUFFIX = "/move_arm" |
static const std::string | object_manipulator::MOVE_ARM_CONSTRAINED_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" |
static const std::string | object_manipulator::MOVE_ARM_PLANNER_ID = "SBLkConfig1" |
static const std::string | object_manipulator::MOVE_ARM_PLANNER_SERVICE_NAME = "ompl_planning/plan_kinematic_path" |
static const std::string | object_manipulator::NORMALIZE_SERVICE_NAME = "trajectory_filter_unnormalizer/filter_trajectory" |
static const double | object_manipulator::OBJECT_POSITION_TOLERANCE_X = 0.02 |
static const double | object_manipulator::OBJECT_POSITION_TOLERANCE_Y = 0.02 |
static const double | object_manipulator::OBJECT_POSITION_TOLERANCE_Z = 0.02 |
static const std::string | object_manipulator::POINT_HEAD_ACTION_TOPIC = "/head_traj_controller/point_head_action" |
static const std::string | object_manipulator::REACTIVE_GRASP_ACTION_SUFFIX = "/reactive_grasp" |
static const std::string | object_manipulator::REACTIVE_LIFT_ACTION_SUFFIX = "/reactive_lift" |
static const std::string | object_manipulator::REACTIVE_PLACE_ACTION_SUFFIX = "/reactive_place" |
static const std::string | object_manipulator::RESET_COLLISION_MAP_SERVICE_NAME = "collider_node/reset" |
static const std::string | object_manipulator::SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff" |
static const std::string | object_manipulator::SWITCH_CONTROLLER_SERVICE_NAME = "/switch_controller" |
static const std::string | object_manipulator::TRAJECTORY_ACTION_SUFFIX = "/joint_trajectory" |