7 #include <std_msgs/Bool.h>
13 #include <dynamic_tf_publisher/SetDynamicTF.h>
15 using namespace visualization_msgs;
20 void processFeedback(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
21 void makeControlMarker(
bool fixed );
22 void set_pose_cb(
const geometry_msgs::PoseStampedConstPtr &
msg );
23 void show_marker_cb (
const std_msgs::BoolConstPtr &
msg);
24 void markerUpdate ( std_msgs::Header
header, geometry_msgs::Pose
pose);
25 void publish_pose_cb(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
26 void callDynamicTf(
const std_msgs::Header&
header,
27 const std::string& child_frame,
28 const geometry_msgs::Transform&
pose,
29 bool until_success =
false);
35 std::shared_ptr<interactive_markers::InteractiveMarkerServer>
server_;
61 std::map<std::string, double> color_map;
74 pnh_.
param(
"center_marker_pose", pose_v, pose_v);
101 geometry_msgs::PoseStamped ps;
102 ps.header = feedback->header;
103 ps.pose = feedback->pose;
109 geometry_msgs::PoseStamped in_pose(*
msg);
110 geometry_msgs::PoseStamped out_pose;
113 out_pose.header.stamp =
msg->header.stamp;
114 server_->setPose(
"urdf_control_marker", out_pose.pose, out_pose.header);
135 const std_msgs::Header& header,
136 const std::string& child_frame,
137 const geometry_msgs::Transform& transform,
140 dynamic_tf_publisher::SetDynamicTF SetTf;
141 SetTf.request.freq = 20;
142 SetTf.request.cur_tf.header =
header;
143 SetTf.request.cur_tf.child_frame_id = child_frame;
144 SetTf.request.cur_tf.transform = transform;
148 ROS_ERROR(
"Failed to call dynamic_tf: %s => %s",
150 child_frame.c_str());
154 if (!until_success) {
167 geometry_msgs::Transform transform;
168 transform.translation.x =
pose.position.x;
169 transform.translation.y =
pose.position.y;
170 transform.translation.z =
pose.position.z;
171 transform.rotation =
pose.orientation;
174 geometry_msgs::PoseStamped ps;
185 InteractiveMarker int_marker;
189 int_marker.name =
"urdf_control_marker";
193 InteractiveMarkerControl center_marker_control;
194 center_marker_control.name =
"center_marker";
195 center_marker_control.always_visible =
true;
196 center_marker_control.orientation.w = 1.0;
197 center_marker_control.orientation.y = 1.0;
200 center_marker_control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
202 center_marker_control.interaction_mode = InteractiveMarkerControl::MOVE_3D;
204 Marker center_marker;
205 center_marker.type = Marker::MESH_RESOURCE;
210 center_marker.color =
color_;
212 center_marker_control.markers.push_back(center_marker);
213 int_marker.controls.push_back(center_marker_control);
216 InteractiveMarkerControl control;
220 int_marker.name +=
"_fixed";
221 control.orientation_mode = InteractiveMarkerControl::FIXED;
223 control.always_visible =
true;
225 control.orientation.w = 1;
226 control.orientation.x = 1;
227 control.orientation.y = 0;
228 control.orientation.z = 0;
229 control.name =
"rotate_x";
230 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
232 int_marker.controls.push_back(control);
234 control.name =
"move_x";
235 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
236 int_marker.controls.push_back(control);
238 control.orientation.w = 1;
239 control.orientation.x = 0;
240 control.orientation.y = 1;
241 control.orientation.z = 0;
242 control.name =
"rotate_z";
243 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
244 int_marker.controls.push_back(control);
245 control.name =
"move_z";
246 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
248 int_marker.controls.push_back(control);
251 control.orientation.w = 1;
252 control.orientation.x = 0;
253 control.orientation.y = 0;
254 control.orientation.z = 1;
255 control.name =
"rotate_y";
256 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
258 int_marker.controls.push_back(control);
260 control.name =
"move_y";
261 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
262 int_marker.controls.push_back(control);
273 geometry_msgs::Transform transform;
274 transform.rotation.w = 1.0;
279 int main(
int argc,
char** argv)