35 #include <grasping_msgs/GraspPlanningAction.h> 57 grasping_msgs::GraspPlanningResult result;
58 planner_->plan(goal->object, result.grasps);
66 int main(
int argc,
char* argv[])
void executeCallback(const grasping_msgs::GraspPlanningGoalConstPtr &goal)
boost::shared_ptr< server_t > server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
GraspPlannerNode(ros::NodeHandle n)
int main(int argc, char *argv[])
boost::shared_ptr< simple_grasping::ShapeGraspPlanner > planner_
actionlib::SimpleActionServer< grasping_msgs::GraspPlanningAction > server_t
A simple grasp planner that uses the bounding box shape to generate viable grasps.