34 #include <turtlebot_arm_object_manipulation/ObjectDetectionAction.h> 35 #include <turtlebot_arm_object_manipulation/PickAndPlaceAction.h> 64 server_(
"object_controls"),
65 object_detection_action_(
"object_detection", true),
66 pick_and_place_action_(
"pick_and_place", true)
71 object_detection_goal_.frame =
arm_link;
73 pick_and_place_goal_.frame =
arm_link;
75 ROS_INFO(
"Finished initializing, waiting for servers...");
95 ROS_INFO(
"Got object detection callback. Adding objects.");
97 for (
unsigned int i=0; i < result->obj_names.size(); i++)
100 ROS_INFO(
"Added %d objects: '%s'", i, result->obj_names[i].c_str());
108 void feedbackCb(
const InteractiveMarkerFeedbackConstPtr &feedback )
110 switch ( feedback->event_type )
112 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
114 old_pose_ = feedback->pose;
117 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
119 moveObject(old_pose_, feedback->pose);
127 bool moveObject(
const geometry_msgs::Pose& start_pose,
const geometry_msgs::Pose& end_pose)
129 pick_and_place_goal_.pick_pose = start_pose;
130 pick_and_place_goal_.place_pose = end_pose;
144 Marker
makeBox( InteractiveMarker &msg,
float r,
float g,
float b )
148 m.type = Marker::CUBE;
149 m.scale.x = msg.scale;
150 m.scale.y = msg.scale;
151 m.scale.z = msg.scale;
163 InteractiveMarker marker;
165 marker.pose.position.x = x;
166 marker.pose.position.y = y;
167 marker.pose.position.z = z;
170 std::stringstream conv;
174 marker.name =
"object" + conv.str();
176 InteractiveMarkerControl control;
177 control.orientation.w = 1;
178 control.orientation.x = 0;
179 control.orientation.y = 1;
180 control.orientation.z = 0;
181 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
182 marker.controls.push_back( control );
184 control.markers.push_back(
makeBox(marker, .5, .5, .5) );
185 control.always_visible =
true;
186 marker.controls.push_back( control );
195 int main(
int argc,
char** argv)
198 ros::init(argc, argv,
"object_manipulation");
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void addObjects(const actionlib::SimpleClientGoalState &state, const turtlebot_arm_object_manipulation::ObjectDetectionResultConstPtr &result)
actionlib::SimpleActionClient< turtlebot_arm_object_manipulation::ObjectDetectionAction > object_detection_action_
turtlebot_arm_object_manipulation::ObjectDetectionGoal object_detection_goal_
void addObject(float x, float y, float z, int n)
geometry_msgs::Pose old_pose_
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
turtlebot_arm_object_manipulation::PickAndPlaceGoal pick_and_place_goal_
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
actionlib::SimpleActionClient< turtlebot_arm_object_manipulation::PickAndPlaceAction > pick_and_place_action_
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
const std::string arm_link
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
interactive_markers::InteractiveMarkerServer server_
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
void feedbackCb(const InteractiveMarkerFeedbackConstPtr &feedback)
SimpleClientGoalState getState() const
ObjectManipulationAction()
bool moveObject(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)