Public Member Functions | Private Attributes
turtlebot_arm_block_manipulation::PickAndPlaceServer Class Reference

List of all members.

Public Member Functions

float fRand (float min, float max)
void goalCB ()
bool moveArmTo (const std::string &target)
bool moveArmTo (const geometry_msgs::Pose &target)
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)
bool setGripper (float opening)

Private Attributes

std::string action_name_
moveit::planning_interface::MoveGroup arm_
std::string arm_link
actionlib::SimpleActionServer
< turtlebot_arm_block_manipulation::PickAndPlaceAction > 
as_
turtlebot_arm_block_manipulation::PickAndPlaceFeedback feedback_
turtlebot_arm_block_manipulation::PickAndPlaceGoalConstPtr goal_
moveit::planning_interface::MoveGroup 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

Definition at line 70 of file pick_and_place_action_server.cpp.


Member Function Documentation

float turtlebot_arm_block_manipulation::PickAndPlaceServer::fRand ( float  min,
float  max 
) [inline]

Definition at line 299 of file pick_and_place_action_server.cpp.

Definition at line 82 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_block_manipulation::PickAndPlaceServer::moveArmTo ( const std::string &  target) [inline]

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 181 of file pick_and_place_action_server.cpp.

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 209 of file pick_and_place_action_server.cpp.

Definition at line 120 of file pick_and_place_action_server.cpp.

Definition at line 113 of file pick_and_place_action_server.cpp.

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

Definition at line 106 of file pick_and_place_action_server.cpp.

Set gripper opening.

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

Definition at line 276 of file pick_and_place_action_server.cpp.


Member Data Documentation

Definition at line 50 of file pick_and_place_action_server.cpp.

Definition at line 60 of file pick_and_place_action_server.cpp.

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.

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.

Definition at line 61 of file pick_and_place_action_server.cpp.

Definition at line 66 of file pick_and_place_action_server.cpp.

Definition at line 65 of file pick_and_place_action_server.cpp.

Definition at line 48 of file pick_and_place_action_server.cpp.

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.

Definition at line 56 of file pick_and_place_action_server.cpp.

Definition at line 67 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 Thu Jun 6 2019 20:54:14