37 #include <turtlebot_arm_block_manipulation/InteractiveBlockManipulationAction.h> 38 #include <geometry_msgs/PoseArray.h> 55 turtlebot_arm_block_manipulation::InteractiveBlockManipulationFeedback
feedback_;
56 turtlebot_arm_block_manipulation::InteractiveBlockManipulationResult
result_;
57 turtlebot_arm_block_manipulation::InteractiveBlockManipulationGoalConstPtr
goal_;
64 geometry_msgs::PoseArrayConstPtr
msg_;
77 nh_(
"~"), server_(
"block_controls"), as_(name, false), action_name_(name), initialized_(false), block_size(0)
80 nh_.
param<
double>(
"bump_size", bump_size, 0.005);
88 block_sub_ = nh_.
subscribe(
"/turtlebot_blocks", 1, &InteractiveManipulationServer::addBlocks,
this);
89 pick_and_place_pub_ = nh_.
advertise< geometry_msgs::PoseArray >(
"/pick_and_place", 1,
true);
98 ROS_INFO(
"[interactive manipulation] Received goal! %f, %s", goal_->block_size, goal_->frame.c_str());
100 block_size = goal_->block_size;
101 arm_link = goal_->frame;
109 ROS_INFO(
"%s: Preempted", action_name_.c_str());
114 void addBlocks(
const geometry_msgs::PoseArrayConstPtr& msg)
119 ROS_INFO(
"Got block detection callback. Adding blocks.");
120 geometry_msgs::Pose block;
123 for (
unsigned int i=0; i < msg->poses.size(); i++)
125 block = msg->poses[i];
126 addBlock(block, i, active, msg->header.frame_id);
138 void feedbackCb(
const InteractiveMarkerFeedbackConstPtr &feedback )
142 ROS_INFO(
"Got feedback but not active!");
145 switch ( feedback->event_type )
147 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
149 old_pose_ = feedback->pose;
152 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
154 moveBlock(old_pose_, feedback->pose);
161 void moveBlock(
const geometry_msgs::Pose& start_pose,
const geometry_msgs::Pose& end_pose)
164 geometry_msgs::Pose start_pose_bumped, end_pose_bumped;
165 start_pose_bumped = start_pose;
167 start_pose_bumped.position.z -= block_size/2.0 - bump_size;
169 result_.pickup_pose = start_pose_bumped;
171 end_pose_bumped = end_pose;
172 end_pose_bumped.position.z -= block_size/2.0 - bump_size;
173 result_.place_pose = end_pose_bumped;
176 geometry_msgs::PoseArray msg;
179 msg.poses.push_back(start_pose_bumped);
180 msg.poses.push_back(end_pose_bumped);
182 pick_and_place_pub_.
publish(msg);
191 Marker
makeBox( InteractiveMarker &msg,
float r,
float g,
float b )
195 m.type = Marker::CUBE;
196 m.scale.x = msg.scale;
197 m.scale.y = msg.scale;
198 m.scale.z = msg.scale;
208 void addBlock(
const geometry_msgs::Pose pose,
int n,
bool active, std::string link)
210 InteractiveMarker marker;
211 marker.header.frame_id = link;
215 std::stringstream conv;
219 marker.name =
"block" + conv.str();
221 InteractiveMarkerControl control;
222 control.orientation.w = 1;
223 control.orientation.x = 0;
224 control.orientation.y = 1;
225 control.orientation.z = 0;
226 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
229 marker.controls.push_back( control );
231 control.markers.push_back(
makeBox(marker, .5, .5, .5) );
232 control.always_visible =
true;
233 marker.controls.push_back( control );
237 server_.
setCallback( marker.name, boost::bind( &InteractiveManipulationServer::feedbackCb,
this, _1 ));
244 int main(
int argc,
char** argv)
247 ros::init(argc, argv,
"interactive_manipulation_action_server");
boost::shared_ptr< const Goal > acceptNewGoal()
turtlebot_arm_block_manipulation::InteractiveBlockManipulationGoalConstPtr goal_
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)
void publish(const boost::shared_ptr< M > &message) const
void addBlock(const geometry_msgs::Pose pose, int n, bool active, std::string link)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber block_sub_
int main(int argc, char **argv)
void addBlocks(const geometry_msgs::PoseArrayConstPtr &msg)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
InteractiveManipulationServer(const std::string name)
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void moveBlock(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
void registerPreemptCallback(boost::function< void()> cb)
geometry_msgs::PoseArrayConstPtr msg_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
turtlebot_arm_block_manipulation::InteractiveBlockManipulationResult result_
actionlib::SimpleActionServer< turtlebot_arm_block_manipulation::InteractiveBlockManipulationAction > as_
void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
turtlebot_arm_block_manipulation::InteractiveBlockManipulationFeedback feedback_
interactive_markers::InteractiveMarkerServer server_
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
ros::Publisher pick_and_place_pub_
geometry_msgs::Pose old_pose_
void registerGoalCallback(boost::function< void()> cb)
const std::string arm_link
void feedbackCb(const InteractiveMarkerFeedbackConstPtr &feedback)