Public Member Functions | Private Member Functions | Private Attributes | List of all members
turtlebot_arm_object_manipulation::PickAndPlaceServer Class Reference

Public Member Functions

void goalCB ()
 
bool pick (const std::string &obj_name, geometry_msgs::PoseStamped &pose)
 
bool pickAndPlace (const std::string &obj_name, geometry_msgs::PoseStamped &pick_pose, geometry_msgs::PoseStamped &place_pose)
 
 PickAndPlaceServer (const std::string name)
 
bool place (const std::string &obj_name, const geometry_msgs::PoseStamped &pose, double pick_position_z)
 
void preemptCB ()
 
 ~PickAndPlaceServer ()
 

Private Member Functions

float fRand (float min, float max)
 
const char * mec2str (const moveit::planning_interface::MoveItErrorCode &mec)
 
bool setGripper (float opening, bool wait_for_complete=true)
 
bool transformPose (const std::string &in_frame, const std::string &out_frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose)
 
bool validateTargetPose (geometry_msgs::PoseStamped &target, bool compensate_backlash, int attempt=0)
 

Private Attributes

std::string action_name_
 
moveit::planning_interface::MoveGroupInterface arm_
 
std::string arm_link
 
actionlib::SimpleActionServer< turtlebot_arm_object_manipulation::PickAndPlaceAction > as_
 
double attach_time
 
ros::ServiceClient clear_octomap_srv_
 
double detach_time
 
std_srvs::Empty empty_srv_
 
turtlebot_arm_object_manipulation::PickAndPlaceFeedback feedback_
 
turtlebot_arm_object_manipulation::PickAndPlaceGoalConstPtr goal_
 
moveit::planning_interface::MoveGroupInterface gripper_
 
double gripper_open
 
const int PICK_ATTEMPTS = 5
 
const int PLACE_ATTEMPTS = PICK_ATTEMPTS
 
moveit::planning_interface::PlanningSceneInterface planning_scene_interface_
 
turtlebot_arm_object_manipulation::PickAndPlaceResult result_
 
ros::Publisher target_pose_pub_
 
tf::TransformListener tf_listener_
 
double z_backlash
 

Detailed Description

Definition at line 56 of file pick_and_place_action_server.cpp.

Constructor & Destructor Documentation

turtlebot_arm_object_manipulation::PickAndPlaceServer::PickAndPlaceServer ( const std::string  name)
inline

Definition at line 90 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::PickAndPlaceServer::~PickAndPlaceServer ( )
inline

Definition at line 114 of file pick_and_place_action_server.cpp.

Member Function Documentation

float turtlebot_arm_object_manipulation::PickAndPlaceServer::fRand ( float  min,
float  max 
)
inlineprivate

Definition at line 494 of file pick_and_place_action_server.cpp.

void turtlebot_arm_object_manipulation::PickAndPlaceServer::goalCB ( )
inline

Definition at line 119 of file pick_and_place_action_server.cpp.

const char* turtlebot_arm_object_manipulation::PickAndPlaceServer::mec2str ( const moveit::planning_interface::MoveItErrorCode mec)
inlineprivate

Definition at line 499 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::pick ( const std::string &  obj_name,
geometry_msgs::PoseStamped &  pose 
)
inline

Definition at line 177 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::pickAndPlace ( const std::string &  obj_name,
geometry_msgs::PoseStamped &  pick_pose,
geometry_msgs::PoseStamped &  place_pose 
)
inline

Definition at line 155 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::place ( const std::string &  obj_name,
const geometry_msgs::PoseStamped &  pose,
double  pick_position_z 
)
inline

Definition at line 302 of file pick_and_place_action_server.cpp.

void turtlebot_arm_object_manipulation::PickAndPlaceServer::preemptCB ( )
inline

Definition at line 145 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::setGripper ( float  opening,
bool  wait_for_complete = true 
)
inlineprivate

Set gripper opening.

Parameters
openingPhysical opening of the gripper, in meters
wait_for_completeWait or not for the execution of the trajectory to complete
Returns
True of success, false otherwise

Definition at line 472 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::transformPose ( const std::string &  in_frame,
const std::string &  out_frame,
const geometry_msgs::PoseStamped &  in_pose,
geometry_msgs::PoseStamped &  out_pose 
)
inlineprivate

Definition at line 557 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::PickAndPlaceServer::validateTargetPose ( geometry_msgs::PoseStamped &  target,
bool  compensate_backlash,
int  attempt = 0 
)
inlineprivate

Convert a simple 3D point into a valid pick/place pose. The orientation Euler angles are calculated as a function of the x and y coordinates, plus some random variations increasing with the number of attempts to improve our chances of successful planning.

Parameters
targetPose target to validate
compensate_backlashIncrement z to cope with backlash and low pitch poses
attemptThe actual attempts number
Returns
True of success, false otherwise

Definition at line 418 of file pick_and_place_action_server.cpp.

Member Data Documentation

std::string turtlebot_arm_object_manipulation::PickAndPlaceServer::action_name_
private

Definition at line 60 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_object_manipulation::PickAndPlaceServer::arm_
private

Definition at line 73 of file pick_and_place_action_server.cpp.

std::string turtlebot_arm_object_manipulation::PickAndPlaceServer::arm_link
private

Definition at line 80 of file pick_and_place_action_server.cpp.

actionlib::SimpleActionServer<turtlebot_arm_object_manipulation::PickAndPlaceAction> turtlebot_arm_object_manipulation::PickAndPlaceServer::as_
private

Definition at line 59 of file pick_and_place_action_server.cpp.

double turtlebot_arm_object_manipulation::PickAndPlaceServer::attach_time
private

Definition at line 82 of file pick_and_place_action_server.cpp.

ros::ServiceClient turtlebot_arm_object_manipulation::PickAndPlaceServer::clear_octomap_srv_
private

Definition at line 68 of file pick_and_place_action_server.cpp.

double turtlebot_arm_object_manipulation::PickAndPlaceServer::detach_time
private

Definition at line 83 of file pick_and_place_action_server.cpp.

std_srvs::Empty turtlebot_arm_object_manipulation::PickAndPlaceServer::empty_srv_
private

Definition at line 66 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::PickAndPlaceFeedback turtlebot_arm_object_manipulation::PickAndPlaceServer::feedback_
private

Definition at line 62 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::PickAndPlaceGoalConstPtr turtlebot_arm_object_manipulation::PickAndPlaceServer::goal_
private

Definition at line 64 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_object_manipulation::PickAndPlaceServer::gripper_
private

Definition at line 74 of file pick_and_place_action_server.cpp.

double turtlebot_arm_object_manipulation::PickAndPlaceServer::gripper_open
private

Definition at line 81 of file pick_and_place_action_server.cpp.

const int turtlebot_arm_object_manipulation::PickAndPlaceServer::PICK_ATTEMPTS = 5
private

Definition at line 86 of file pick_and_place_action_server.cpp.

const int turtlebot_arm_object_manipulation::PickAndPlaceServer::PLACE_ATTEMPTS = PICK_ATTEMPTS
private

Definition at line 87 of file pick_and_place_action_server.cpp.

moveit::planning_interface::PlanningSceneInterface turtlebot_arm_object_manipulation::PickAndPlaceServer::planning_scene_interface_
private

Definition at line 77 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::PickAndPlaceResult turtlebot_arm_object_manipulation::PickAndPlaceServer::result_
private

Definition at line 63 of file pick_and_place_action_server.cpp.

ros::Publisher turtlebot_arm_object_manipulation::PickAndPlaceServer::target_pose_pub_
private

Definition at line 67 of file pick_and_place_action_server.cpp.

tf::TransformListener turtlebot_arm_object_manipulation::PickAndPlaceServer::tf_listener_
private

Definition at line 70 of file pick_and_place_action_server.cpp.

double turtlebot_arm_object_manipulation::PickAndPlaceServer::z_backlash
private

Definition at line 84 of file pick_and_place_action_server.cpp.


The documentation for this class was generated from the following file:


turtlebot_arm_object_manipulation
Author(s): Jorge Santos
autogenerated on Fri Feb 7 2020 03:56:40