Oversees the grasping app; bundles together functionality in higher level calls. More...
#include <object_manipulator.h>
Public Member Functions | |
ObjectManipulator () | |
Initializes ros clients as needed. | |
void | pickup (const object_manipulation_msgs::PickupGoal::ConstPtr &pickup_goal, actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > *action_server) |
Attempts to grasp the specified object. | |
void | place (const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal, actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > *action_server) |
Attempts to place the specified object. | |
~ObjectManipulator () | |
Private Attributes | |
std::string | default_cluster_planner_ |
The name of the service to be used by default for grasp planning on point cloud objects. | |
std::string | default_database_planner_ |
The name of the service to be used by default for grasp planning on database objects. | |
std::string | default_probabilistic_planner_ |
The name of the service to be used by default for grasp planning on probabilistic recognition results. | |
GraspExecutorWithApproach * | grasp_executor_with_approach_ |
Instance of the grasp executor with approach. | |
MultiArmServiceWrapper < object_manipulation_msgs::GraspPlanning > | grasp_planning_services_ |
Wrapper for multiple grasp planning services with different names. | |
GraspMarkerPublisher * | marker_pub_ |
Publisher for grasp markers, or NULL if publishing is disabled. | |
PlaceExecutor * | place_executor_ |
Instance of the executor used for placing objects. | |
ros::NodeHandle | priv_nh_ |
The private ROS node handle. | |
bool | randomize_grasps_ |
Whether the order in which grasps are tried should be randomized first. Debug purposes. | |
ReactiveGraspExecutor * | reactive_grasp_executor_ |
Instance of the reactive grasp executor. | |
ReactivePlaceExecutor * | reactive_place_executor_ |
Instance of the executor used for reactive placing of objects. | |
ros::NodeHandle | root_nh_ |
The root ROS node handle. |
Oversees the grasping app; bundles together functionality in higher level calls.
Also wraps the functionality in action replies, with the actual server passed in from the caller so we keep ROS instantiations somewhat separated.
Definition at line 59 of file object_manipulator.h.
Initializes ros clients as needed.
Definition at line 61 of file object_manipulator.cpp.
Definition at line 88 of file object_manipulator.cpp.
void object_manipulator::ObjectManipulator::pickup | ( | const object_manipulation_msgs::PickupGoal::ConstPtr & | pickup_goal, |
actionlib::SimpleActionServer< object_manipulation_msgs::PickupAction > * | action_server | ||
) |
Attempts to grasp the specified object.
Definition at line 97 of file object_manipulator.cpp.
void object_manipulator::ObjectManipulator::place | ( | const object_manipulation_msgs::PlaceGoal::ConstPtr & | place_goal, |
actionlib::SimpleActionServer< object_manipulation_msgs::PlaceAction > * | action_server | ||
) |
Attempts to place the specified object.
Definition at line 247 of file object_manipulator.cpp.
std::string object_manipulator::ObjectManipulator::default_cluster_planner_ [private] |
The name of the service to be used by default for grasp planning on point cloud objects.
Definition at line 95 of file object_manipulator.h.
std::string object_manipulator::ObjectManipulator::default_database_planner_ [private] |
The name of the service to be used by default for grasp planning on database objects.
Definition at line 92 of file object_manipulator.h.
std::string object_manipulator::ObjectManipulator::default_probabilistic_planner_ [private] |
The name of the service to be used by default for grasp planning on probabilistic recognition results.
Definition at line 98 of file object_manipulator.h.
GraspExecutorWithApproach* object_manipulator::ObjectManipulator::grasp_executor_with_approach_ [private] |
Instance of the grasp executor with approach.
Definition at line 80 of file object_manipulator.h.
MultiArmServiceWrapper<object_manipulation_msgs::GraspPlanning> object_manipulator::ObjectManipulator::grasp_planning_services_ [private] |
Wrapper for multiple grasp planning services with different names.
Not really a wrapper for multiple arms, but a wrapper for multiple services with different names but fulfilling the same task.
Definition at line 71 of file object_manipulator.h.
Publisher for grasp markers, or NULL if publishing is disabled.
Definition at line 74 of file object_manipulator.h.
Instance of the executor used for placing objects.
Definition at line 86 of file object_manipulator.h.
The private ROS node handle.
Definition at line 63 of file object_manipulator.h.
Whether the order in which grasps are tried should be randomized first. Debug purposes.
Definition at line 77 of file object_manipulator.h.
Instance of the reactive grasp executor.
Definition at line 83 of file object_manipulator.h.
Instance of the executor used for reactive placing of objects.
Definition at line 89 of file object_manipulator.h.
The root ROS node handle.
Definition at line 66 of file object_manipulator.h.