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

Public Member Functions

void goalCB ()
 
 MoveToTargetServer (const std::string name)
 
void preemptCB ()
 
 ~MoveToTargetServer ()
 

Private Member Functions

float fRand (float min, float max)
 
bool moveArmTo (const std::string &target)
 
bool moveArmTo (const geometry_msgs::PoseStamped &target)
 
bool setGripper (float opening, bool wait_for_complete=true)
 

Private Attributes

std::string action_name_
 
moveit::planning_interface::MoveGroupInterface arm_
 
actionlib::SimpleActionServer< turtlebot_arm_object_manipulation::MoveToTargetAction > as_
 
turtlebot_arm_object_manipulation::MoveToTargetFeedback feedback_
 
turtlebot_arm_object_manipulation::MoveToTargetGoalConstPtr goal_
 
moveit::planning_interface::MoveGroupInterface gripper_
 
turtlebot_arm_object_manipulation::MoveToTargetResult result_
 
ros::Publisher target_pose_pub_
 

Detailed Description

Action server providing more basic arm motions:

Definition at line 588 of file pick_and_place_action_server.cpp.

Constructor & Destructor Documentation

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

Definition at line 605 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::MoveToTargetServer::~MoveToTargetServer ( )
inline

Definition at line 618 of file pick_and_place_action_server.cpp.

Member Function Documentation

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

Definition at line 789 of file pick_and_place_action_server.cpp.

void turtlebot_arm_object_manipulation::MoveToTargetServer::goalCB ( )
inline

Definition at line 623 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::MoveToTargetServer::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 667 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::MoveToTargetServer::moveArmTo ( const geometry_msgs::PoseStamped &  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 695 of file pick_and_place_action_server.cpp.

void turtlebot_arm_object_manipulation::MoveToTargetServer::preemptCB ( )
inline

Definition at line 651 of file pick_and_place_action_server.cpp.

bool turtlebot_arm_object_manipulation::MoveToTargetServer::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 767 of file pick_and_place_action_server.cpp.

Member Data Documentation

std::string turtlebot_arm_object_manipulation::MoveToTargetServer::action_name_
private

Definition at line 592 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_object_manipulation::MoveToTargetServer::arm_
private

Definition at line 601 of file pick_and_place_action_server.cpp.

actionlib::SimpleActionServer<turtlebot_arm_object_manipulation::MoveToTargetAction> turtlebot_arm_object_manipulation::MoveToTargetServer::as_
private

Definition at line 591 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::MoveToTargetFeedback turtlebot_arm_object_manipulation::MoveToTargetServer::feedback_
private

Definition at line 594 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::MoveToTargetGoalConstPtr turtlebot_arm_object_manipulation::MoveToTargetServer::goal_
private

Definition at line 596 of file pick_and_place_action_server.cpp.

moveit::planning_interface::MoveGroupInterface turtlebot_arm_object_manipulation::MoveToTargetServer::gripper_
private

Definition at line 602 of file pick_and_place_action_server.cpp.

turtlebot_arm_object_manipulation::MoveToTargetResult turtlebot_arm_object_manipulation::MoveToTargetServer::result_
private

Definition at line 595 of file pick_and_place_action_server.cpp.

ros::Publisher turtlebot_arm_object_manipulation::MoveToTargetServer::target_pose_pub_
private

Definition at line 598 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