InHandObjectModeler Class Reference

List of all members.

Public Member Functions

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 ()
bool moveArmAway (std::string arm_name)
 Move the arm to get it away from stuff.
bool moveArmIntoView (std::string arm_name)
 Move the arm to a fixed position in front of the head (keep old orientation).
void pointHead (std::string arm_name)
bool turnArmInwards (std::string arm_name, sensor_msgs::PointCloud2 &object_in_hand, int keep_level)
 Turn the gripper so it's facing towards the robot.

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::ModelObjectInHandResult model_object_result_
 Result 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 (  )  [inline]

Definition at line 87 of file create_object_model_server.cpp.


Member Function Documentation

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 217 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 110 of file create_object_model_server.cpp.

bool InHandObjectModeler::moveArmAway ( std::string  arm_name  )  [inline]

Move the arm to get it away from stuff.

Definition at line 387 of file create_object_model_server.cpp.

bool InHandObjectModeler::moveArmIntoView ( std::string  arm_name  )  [inline]

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

Definition at line 258 of file create_object_model_server.cpp.

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

Definition at line 233 of file create_object_model_server.cpp.

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

Turn the gripper so it's facing towards the robot.

Definition at line 274 of file create_object_model_server.cpp.


Member Data Documentation

tabletop_collision_map_processing::CollisionMapInterface InHandObjectModeler::collision_map_interface_ [private]

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

Definition at line 80 of file create_object_model_server.cpp.

object_manipulator::MechanismInterface InHandObjectModeler::mech_interface_ [private]

Mechanism interface for moving the arms/head.

Definition at line 77 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.

Result for the action.

Definition at line 68 of file create_object_model_server.cpp.

ros::NodeHandle InHandObjectModeler::priv_nh_ [private]

Node handle in the private namespace.

Definition at line 62 of file create_object_model_server.cpp.

ros::Publisher InHandObjectModeler::pub_cloud [private]

Publisher for the current object in hand point cloud.

Definition at line 71 of file create_object_model_server.cpp.

ros::NodeHandle InHandObjectModeler::root_nh_ [private]

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 74 of file create_object_model_server.cpp.

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

Definition at line 83 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


pr2_create_object_model
Author(s): Kaijen Hsiao
autogenerated on Fri Jan 11 09:35:26 2013