34 #include <turtlebot_arm_block_manipulation/BlockDetectionAction.h> 35 #include <turtlebot_arm_block_manipulation/PickAndPlaceAction.h> 71 server_(
"block_controls"),
72 block_detection_action_(
"block_detection", true),
73 pick_and_place_action_(
"pick_and_place", true)
78 block_detection_goal_.frame =
arm_link;
79 block_detection_goal_.table_height =
z_down;
82 pick_and_place_goal_.frame =
arm_link;
83 pick_and_place_goal_.z_up =
z_up;
87 ROS_INFO(
"Finished initializing, waiting for servers...");
107 ROS_INFO(
"Got block detection callback. Adding blocks.");
108 geometry_msgs::Pose block;
110 for (
unsigned int i=0; i < result->blocks.poses.size(); i++)
112 block = result->blocks.poses[i];
113 addBlock(block.position.x, block.position.y, block.position.z, i);
122 void feedbackCb(
const InteractiveMarkerFeedbackConstPtr &feedback )
124 switch ( feedback->event_type )
126 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
128 old_pose_ = feedback->pose;
131 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
133 moveBlock(old_pose_, feedback->pose);
141 bool moveBlock(
const geometry_msgs::Pose& start_pose,
const geometry_msgs::Pose& end_pose)
143 pick_and_place_goal_.pickup_pose = start_pose;
144 pick_and_place_goal_.place_pose = end_pose;
160 Marker
makeBox( InteractiveMarker &msg,
float r,
float g,
float b )
164 m.type = Marker::CUBE;
165 m.scale.x = msg.scale;
166 m.scale.y = msg.scale;
167 m.scale.z = msg.scale;
179 InteractiveMarker marker;
181 marker.pose.position.x = x;
182 marker.pose.position.y = y;
183 marker.pose.position.z = z;
186 std::stringstream conv;
190 marker.name =
"block" + conv.str();
192 InteractiveMarkerControl control;
193 control.orientation.w = 1;
194 control.orientation.x = 0;
195 control.orientation.y = 1;
196 control.orientation.z = 0;
197 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
198 marker.controls.push_back( control );
200 control.markers.push_back(
makeBox(marker, .5, .5, .5) );
201 control.always_visible =
true;
202 marker.controls.push_back( control );
211 int main(
int argc,
char** argv)
214 ros::init(argc, argv,
"block_manipulation");
turtlebot_arm_block_manipulation::BlockDetectionGoal block_detection_goal_
int main(int argc, char **argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void addBlock(float x, float y, float z, int n)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void feedbackCb(const InteractiveMarkerFeedbackConstPtr &feedback)
actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::BlockDetectionAction > block_detection_action_
geometry_msgs::Pose old_pose_
turtlebot_arm_block_manipulation::PickAndPlaceGoal pick_and_place_goal_
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
const double gripper_closed
BlockManipulationAction()
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
const double gripper_open
interactive_markers::InteractiveMarkerServer server_
const std::string arm_link
void addBlocks(const actionlib::SimpleClientGoalState &state, const turtlebot_arm_block_manipulation::BlockDetectionResultConstPtr &result)
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)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
SimpleClientGoalState getState() const
actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::PickAndPlaceAction > pick_and_place_action_
bool moveBlock(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)