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_ |
Action server providing more basic arm motions:
Definition at line 588 of file pick_and_place_action_server.cpp.
|
inline |
Definition at line 605 of file pick_and_place_action_server.cpp.
|
inline |
Definition at line 618 of file pick_and_place_action_server.cpp.
|
inlineprivate |
Definition at line 789 of file pick_and_place_action_server.cpp.
|
inline |
Definition at line 623 of file pick_and_place_action_server.cpp.
|
inlineprivate |
Move arm to a named configuration, normally described in the robot semantic description SRDF file.
| target | Named target to achieve |
Definition at line 667 of file pick_and_place_action_server.cpp.
|
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.
| target | Pose target to achieve |
Definition at line 695 of file pick_and_place_action_server.cpp.
|
inline |
Definition at line 651 of file pick_and_place_action_server.cpp.
|
inlineprivate |
Set gripper opening.
| opening | Physical opening of the gripper, in meters |
| wait_for_complete | Wait or not for the execution of the trajectory to complete |
Definition at line 767 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 592 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 601 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 591 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 594 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 596 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 602 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 595 of file pick_and_place_action_server.cpp.
|
private |
Definition at line 598 of file pick_and_place_action_server.cpp.