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::Publisher | pub_pc2 |
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) |
Definition at line 53 of file create_object_model_server.cpp.
InHandObjectModeler::InHandObjectModeler | ( | std::string | name | ) | [inline] |
Definition at line 89 of file create_object_model_server.cpp.
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 207 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 258 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 113 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 517 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 298 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 275 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 351 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 406 of file create_object_model_server.cpp.
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 82 of file create_object_model_server.cpp.
Mechanism interface for moving the arms/head.
Definition at line 79 of file create_object_model_server.cpp.
actionlib::SimpleActionServer<pr2_create_object_model::ModelObjectInHandAction> InHandObjectModeler::model_object_action_server_ [private] |
Action server for the model_object_in_hand_action.
Definition at line 65 of file create_object_model_server.cpp.
pr2_create_object_model::ModelObjectInHandFeedback InHandObjectModeler::model_object_feedback_ [private] |
Definition at line 69 of file create_object_model_server.cpp.
pr2_create_object_model::ModelObjectInHandResult InHandObjectModeler::model_object_result_ [private] |
Result and feedback 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 72 of file create_object_model_server.cpp.
ros::Publisher InHandObjectModeler::pub_pc2 [private] |
Definition at line 73 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.
std::string InHandObjectModeler::segment_object_service_name_ [private] |
Name of the segment_object_in_hand service.
Definition at line 76 of file create_object_model_server.cpp.
bool InHandObjectModeler::stereo_ [private] |
Which stereo camera we're using (true = narrow_stereo, false = kinect)
Definition at line 85 of file create_object_model_server.cpp.