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

Public Member Functions

void goalCB ()
 
void pickAndPlace (const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
 
 PickAndPlaceServer (const std::string name)
 
void preemptCB ()
 
void sendGoalFromTopic (const geometry_msgs::PoseArrayConstPtr &msg)
 

Private Member Functions

float fRand (float min, float max)
 
bool moveArmTo (const std::string &target)
 
bool moveArmTo (const geometry_msgs::Pose &target)
 
bool setGripper (float opening)
 

Private Attributes

std::string action_name_
 
moveit::planning_interface::MoveGroupInterface arm_
 
std::string arm_link
 
actionlib::SimpleActionServer< turtlebot_arm_block_manipulation::PickAndPlaceAction > as_
 
double attach_time
 
double detach_time
 
turtlebot_arm_block_manipulation::PickAndPlaceFeedback feedback_
 
turtlebot_arm_block_manipulation::PickAndPlaceGoalConstPtr goal_
 
moveit::planning_interface::MoveGroupInterface gripper_
 
double gripper_closed
 
double gripper_open
 
ros::NodeHandle nh_
 
ros::Subscriber pick_and_place_sub_
 
turtlebot_arm_block_manipulation::PickAndPlaceResult result_
 
ros::Publisher target_pose_pub_
 
double z_up
 

Detailed Description

Definition at line 44 of file pick_and_place_action_server.cpp.

Constructor & Destructor Documentation

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

Definition at line 72 of file pick_and_place_action_server.cpp.

Member Function Documentation

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

Definition at line 309 of file pick_and_place_action_server.cpp.

void turtlebot_arm_block_manipulation::PickAndPlaceServer::goalCB ( )
inline

Definition at line 88 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_block_manipulation::PickAndPlaceServer::moveArmTo ( const std::string &  target)
inlineprivate

Move arm to a named configuration, normally described in the robot semantic description SRDF file.

Parameters
targetNamed target to achieve
Returns
True of success, false otherwise

Definition at line 187 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_block_manipulation::PickAndPlaceServer::moveArmTo ( const geometry_msgs::Pose target)
inlineprivate

Move arm to a target pose. Only position coordinates are taken into account; the orientation is calculated according to the direction and distance to the target.

Parameters
targetPose target to achieve
Returns
True of success, false otherwise

Definition at line 215 of file pick_and_place_action_server.cpp.

void turtlebot_arm_block_manipulation::PickAndPlaceServer::pickAndPlace ( const geometry_msgs::Pose start_pose,
const geometry_msgs::Pose end_pose 
)
inline

Definition at line 126 of file pick_and_place_action_server.cpp.

void turtlebot_arm_block_manipulation::PickAndPlaceServer::preemptCB ( )
inline

Definition at line 119 of file pick_and_place_action_server.cpp.

void turtlebot_arm_block_manipulation::PickAndPlaceServer::sendGoalFromTopic ( const geometry_msgs::PoseArrayConstPtr &  msg)
inline

Definition at line 112 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_block_manipulation::PickAndPlaceServer::setGripper ( float  opening)
inlineprivate

Set gripper opening.

Parameters
openingPhysical opening of the gripper, in meters
Returns
True of success, false otherwise

Definition at line 287 of file pick_and_place_action_server.cpp.

Member Data Documentation

std::string turtlebot_arm_block_manipulation::PickAndPlaceServer::action_name_
private

Definition at line 50 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_block_manipulation::PickAndPlaceServer::arm_
private

Definition at line 60 of file pick_and_place_action_server.cpp.

std::string turtlebot_arm_block_manipulation::PickAndPlaceServer::arm_link
private

Definition at line 64 of file pick_and_place_action_server.cpp.

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

Definition at line 49 of file pick_and_place_action_server.cpp.

double turtlebot_arm_block_manipulation::PickAndPlaceServer::attach_time
private

Definition at line 67 of file pick_and_place_action_server.cpp.

double turtlebot_arm_block_manipulation::PickAndPlaceServer::detach_time
private

Definition at line 68 of file pick_and_place_action_server.cpp.

turtlebot_arm_block_manipulation::PickAndPlaceFeedback turtlebot_arm_block_manipulation::PickAndPlaceServer::feedback_
private

Definition at line 52 of file pick_and_place_action_server.cpp.

turtlebot_arm_block_manipulation::PickAndPlaceGoalConstPtr turtlebot_arm_block_manipulation::PickAndPlaceServer::goal_
private

Definition at line 54 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_block_manipulation::PickAndPlaceServer::gripper_
private

Definition at line 61 of file pick_and_place_action_server.cpp.

double turtlebot_arm_block_manipulation::PickAndPlaceServer::gripper_closed
private

Definition at line 66 of file pick_and_place_action_server.cpp.

double turtlebot_arm_block_manipulation::PickAndPlaceServer::gripper_open
private

Definition at line 65 of file pick_and_place_action_server.cpp.

ros::NodeHandle turtlebot_arm_block_manipulation::PickAndPlaceServer::nh_
private

Definition at line 48 of file pick_and_place_action_server.cpp.

ros::Subscriber turtlebot_arm_block_manipulation::PickAndPlaceServer::pick_and_place_sub_
private

Definition at line 57 of file pick_and_place_action_server.cpp.

turtlebot_arm_block_manipulation::PickAndPlaceResult turtlebot_arm_block_manipulation::PickAndPlaceServer::result_
private

Definition at line 53 of file pick_and_place_action_server.cpp.

ros::Publisher turtlebot_arm_block_manipulation::PickAndPlaceServer::target_pose_pub_
private

Definition at line 56 of file pick_and_place_action_server.cpp.

double turtlebot_arm_block_manipulation::PickAndPlaceServer::z_up
private

Definition at line 69 of file pick_and_place_action_server.cpp.


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


turtlebot_arm_block_manipulation
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Fri Feb 7 2020 03:56:21