$search

InHandObjectModeler Class Reference

List of all members.

Public Member Functions

bool attachObject (std::string arm_name, sensor_msgs::PointCloud2 object_in_hand, std::string &collision_name)
 Add the object's bounding box to the collision map and attach it to the gripper.
bool callSegmentObjectInHand (std::string arm_name, sensor_msgs::PointCloud2 &object_in_hand)
 Call the segment_object_in_hand_srv service.
void executeCB (const pr2_create_object_model::ModelObjectInHandGoalConstPtr &goal)
 Model object in hand action callback.
 InHandObjectModeler (std::string name)
bool moveArmAway (std::string arm_name, geometry_msgs::Vector3Stamped clear_move)
 Move the arm to get it away from stuff.
bool moveArmIntoView (std::string arm_name, sensor_msgs::PointCloud2 object_in_hand, geometry_msgs::PoseStamped desired_pose)
 Move the arm to a fixed position in front of the head (keep old orientation).
void pointHead (std::string arm_name)
 Point the head at what's in the gripper.
bool rotateObject (std::string arm_name, sensor_msgs::PointCloud2 &object_in_hand)
 Rotate the last arm joint, not trying to keep the object level.
bool turnArmInwards (std::string arm_name, sensor_msgs::PointCloud2 &object_in_hand)
 Turn the gripper so it's facing towards the robot, keeping the gripper level.

Private Attributes

tabletop_collision_map_processing::CollisionMapInterface collision_map_interface_
 Collision interface for adding the object to the collision map, if requested.
object_manipulator::MechanismInterface mech_interface_
 Mechanism interface for moving the arms/head.
actionlib::SimpleActionServer
< pr2_create_object_model::ModelObjectInHandAction
model_object_action_server_
 Action server for the model_object_in_hand_action.
pr2_create_object_model::ModelObjectInHandFeedback model_object_feedback_
pr2_create_object_model::ModelObjectInHandResult model_object_result_
 Result and feedback for the action.
ros::NodeHandle priv_nh_
 Node handle in the private namespace.
ros::Publisher pub_cloud
 Publisher for the current object in hand point cloud.
ros::NodeHandle root_nh_
 Node handle in the root namespace.
std::string segment_object_service_name_
 Name of the segment_object_in_hand service.
bool stereo_
 Which stereo camera we're using (true = narrow_stereo, false = kinect).

Detailed Description

Definition at line 53 of file create_object_model_server.cpp.


Constructor & Destructor Documentation

InHandObjectModeler::InHandObjectModeler ( std::string  name  )  [inline]

Definition at line 88 of file create_object_model_server.cpp.


Member Function Documentation

bool InHandObjectModeler::attachObject ( std::string  arm_name,
sensor_msgs::PointCloud2  object_in_hand,
std::string &  collision_name 
) [inline]

Add the object's bounding box to the collision map and attach it to the gripper.

Definition at line 204 of file create_object_model_server.cpp.

bool InHandObjectModeler::callSegmentObjectInHand ( std::string  arm_name,
sensor_msgs::PointCloud2 object_in_hand 
) [inline]

Call the segment_object_in_hand_srv service.

Definition at line 255 of file create_object_model_server.cpp.

void InHandObjectModeler::executeCB ( const pr2_create_object_model::ModelObjectInHandGoalConstPtr goal  )  [inline]

Model object in hand action callback.

Definition at line 111 of file create_object_model_server.cpp.

bool InHandObjectModeler::moveArmAway ( std::string  arm_name,
geometry_msgs::Vector3Stamped  clear_move 
) [inline]

Move the arm to get it away from stuff.

Definition at line 514 of file create_object_model_server.cpp.

bool InHandObjectModeler::moveArmIntoView ( std::string  arm_name,
sensor_msgs::PointCloud2  object_in_hand,
geometry_msgs::PoseStamped  desired_pose 
) [inline]

Move the arm to a fixed position in front of the head (keep old orientation).

Definition at line 295 of file create_object_model_server.cpp.

void InHandObjectModeler::pointHead ( std::string  arm_name  )  [inline]

Point the head at what's in the gripper.

Definition at line 272 of file create_object_model_server.cpp.

bool InHandObjectModeler::rotateObject ( std::string  arm_name,
sensor_msgs::PointCloud2 object_in_hand 
) [inline]

Rotate the last arm joint, not trying to keep the object level.

Definition at line 348 of file create_object_model_server.cpp.

bool InHandObjectModeler::turnArmInwards ( std::string  arm_name,
sensor_msgs::PointCloud2 object_in_hand 
) [inline]

Turn the gripper so it's facing towards the robot, keeping the gripper level.

Definition at line 403 of file create_object_model_server.cpp.


Member Data Documentation

Collision interface for adding the object to the collision map, if requested.

Definition at line 81 of file create_object_model_server.cpp.

Mechanism interface for moving the arms/head.

Definition at line 78 of file create_object_model_server.cpp.

Action server for the model_object_in_hand_action.

Definition at line 65 of file create_object_model_server.cpp.

Definition at line 69 of file create_object_model_server.cpp.

Result and feedback for the action.

Definition at line 68 of file create_object_model_server.cpp.

Node handle in the private namespace.

Definition at line 62 of file create_object_model_server.cpp.

Publisher for the current object in hand point cloud.

Definition at line 72 of file create_object_model_server.cpp.

Node handle in the root namespace.

Definition at line 59 of file create_object_model_server.cpp.

Name of the segment_object_in_hand service.

Definition at line 75 of file create_object_model_server.cpp.

Which stereo camera we're using (true = narrow_stereo, false = kinect).

Definition at line 84 of file create_object_model_server.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


pr2_create_object_model
Author(s): Kaijen Hsiao
autogenerated on Tue Mar 5 12:38:10 2013