#include <specific_actions.h>
Public Member Functions | |
| SpecificActions () | |
| Constructor. | |
Private Member Functions | |
| void | executeObtainObject (const carl_demos::ObtainObjectGoalConstPtr &goal) |
| Pickup a specified object, if it can be found in front of the robot. | |
| void | recognizedObjectsCallback (const rail_manipulation_msgs::SegmentedObjectList &objects) |
| Store the latest recognized objects. | |
Private Attributes | |
| actionlib::SimpleActionClient < rail_manipulation_msgs::ArmAction > | armClient |
| ros::NodeHandle | n |
| actionlib::SimpleActionServer < carl_demos::ObtainObjectAction > | obtainObjectServer |
| actionlib::SimpleActionClient < rail_manipulation_msgs::PickupAction > | pickupClient |
| rail_manipulation_msgs::SegmentedObjectList | recognizedObjects |
| int | recognizedObjectsCounter |
| boost::mutex | recognizedObjectsMutex |
| ros::Subscriber | recognizedObjectsSubscriber |
| ros::ServiceClient | segmentClient |
| actionlib::SimpleActionClient < rail_manipulation_msgs::StoreAction > | storeClient |
Definition at line 19 of file specific_actions.h.
Constructor.
Definition at line 5 of file specific_actions.cpp.
| void SpecificActions::executeObtainObject | ( | const carl_demos::ObtainObjectGoalConstPtr & | goal | ) | [private] |
Pickup a specified object, if it can be found in front of the robot.
Action server to perform object recognition, followed by a pickup of the specified object, followed by storing the the picked-up object.
| goal | Specification of the object to be obtained. |
Definition at line 21 of file specific_actions.cpp.
| void SpecificActions::recognizedObjectsCallback | ( | const rail_manipulation_msgs::SegmentedObjectList & | objects | ) | [private] |
Store the latest recognized objects.
Stores the latest recognized objects from the segmentation topic.
| objects | The latest recognized objects. |
Definition at line 128 of file specific_actions.cpp.
actionlib::SimpleActionClient<rail_manipulation_msgs::ArmAction> SpecificActions::armClient [private] |
Definition at line 36 of file specific_actions.h.
ros::NodeHandle SpecificActions::n [private] |
Definition at line 30 of file specific_actions.h.
actionlib::SimpleActionServer<carl_demos::ObtainObjectAction> SpecificActions::obtainObjectServer [private] |
Definition at line 39 of file specific_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::PickupAction> SpecificActions::pickupClient [private] |
Definition at line 37 of file specific_actions.h.
rail_manipulation_msgs::SegmentedObjectList SpecificActions::recognizedObjects [private] |
Definition at line 45 of file specific_actions.h.
int SpecificActions::recognizedObjectsCounter [private] |
Definition at line 41 of file specific_actions.h.
boost::mutex SpecificActions::recognizedObjectsMutex [private] |
Definition at line 43 of file specific_actions.h.
Definition at line 32 of file specific_actions.h.
Definition at line 34 of file specific_actions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::StoreAction> SpecificActions::storeClient [private] |
Definition at line 38 of file specific_actions.h.