|
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 () |
|
turtlebot_arm_object_manipulation::PickAndPlaceServer::PickAndPlaceServer |
( |
const std::string |
name | ) |
|
|
inline |
turtlebot_arm_object_manipulation::PickAndPlaceServer::~PickAndPlaceServer |
( |
| ) |
|
|
inline |
float turtlebot_arm_object_manipulation::PickAndPlaceServer::fRand |
( |
float |
min, |
|
|
float |
max |
|
) |
| |
|
inlineprivate |
void turtlebot_arm_object_manipulation::PickAndPlaceServer::goalCB |
( |
| ) |
|
|
inline |
bool turtlebot_arm_object_manipulation::PickAndPlaceServer::pick |
( |
const std::string & |
obj_name, |
|
|
geometry_msgs::PoseStamped & |
pose |
|
) |
| |
|
inline |
bool turtlebot_arm_object_manipulation::PickAndPlaceServer::pickAndPlace |
( |
const std::string & |
obj_name, |
|
|
geometry_msgs::PoseStamped & |
pick_pose, |
|
|
geometry_msgs::PoseStamped & |
place_pose |
|
) |
| |
|
inline |
bool turtlebot_arm_object_manipulation::PickAndPlaceServer::place |
( |
const std::string & |
obj_name, |
|
|
const geometry_msgs::PoseStamped & |
pose, |
|
|
double |
pick_position_z |
|
) |
| |
|
inline |
void turtlebot_arm_object_manipulation::PickAndPlaceServer::preemptCB |
( |
| ) |
|
|
inline |
bool turtlebot_arm_object_manipulation::PickAndPlaceServer::setGripper |
( |
float |
opening, |
|
|
bool |
wait_for_complete = true |
|
) |
| |
|
inlineprivate |
Set gripper opening.
- Parameters
-
opening | Physical opening of the gripper, in meters |
wait_for_complete | Wait 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 |
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
-
target | Pose target to validate |
compensate_backlash | Increment z to cope with backlash and low pitch poses |
attempt | The actual attempts number |
- Returns
- True of success, false otherwise
Definition at line 418 of file pick_and_place_action_server.cpp.
std::string turtlebot_arm_object_manipulation::PickAndPlaceServer::action_name_ |
|
private |
std::string turtlebot_arm_object_manipulation::PickAndPlaceServer::arm_link |
|
private |
double turtlebot_arm_object_manipulation::PickAndPlaceServer::attach_time |
|
private |
ros::ServiceClient turtlebot_arm_object_manipulation::PickAndPlaceServer::clear_octomap_srv_ |
|
private |
double turtlebot_arm_object_manipulation::PickAndPlaceServer::detach_time |
|
private |
std_srvs::Empty turtlebot_arm_object_manipulation::PickAndPlaceServer::empty_srv_ |
|
private |
turtlebot_arm_object_manipulation::PickAndPlaceFeedback turtlebot_arm_object_manipulation::PickAndPlaceServer::feedback_ |
|
private |
turtlebot_arm_object_manipulation::PickAndPlaceGoalConstPtr turtlebot_arm_object_manipulation::PickAndPlaceServer::goal_ |
|
private |
double turtlebot_arm_object_manipulation::PickAndPlaceServer::gripper_open |
|
private |
const int turtlebot_arm_object_manipulation::PickAndPlaceServer::PICK_ATTEMPTS = 5 |
|
private |
const int turtlebot_arm_object_manipulation::PickAndPlaceServer::PLACE_ATTEMPTS = PICK_ATTEMPTS |
|
private |
turtlebot_arm_object_manipulation::PickAndPlaceResult turtlebot_arm_object_manipulation::PickAndPlaceServer::result_ |
|
private |
ros::Publisher turtlebot_arm_object_manipulation::PickAndPlaceServer::target_pose_pub_ |
|
private |
double turtlebot_arm_object_manipulation::PickAndPlaceServer::z_backlash |
|
private |
The documentation for this class was generated from the following file: