42 #include <geometry_msgs/PoseStamped.h> 54 pnh.
param(
"tf_duration", tf_duration, 0.1);
64 pnh.
param(
"frame_id", frame_id, std::string(
"/map"));
67 pnh.
param(
"initial_x", initial_x, 0.0);
68 pnh.
param(
"initial_y", initial_y, 0.0);
69 pnh.
param(
"initial_z", initial_z, 0.0);
73 std::vector<double> initial_orientation;
75 latest_pose_.pose.orientation.x = initial_orientation[0];
76 latest_pose_.pose.orientation.y = initial_orientation[1];
77 latest_pose_.pose.orientation.z = initial_orientation[2];
78 latest_pose_.pose.orientation.w = initial_orientation[3];
85 if (pnh.
hasParam(
"interactive_marker_scale")) {
117 server_->setPose(
"marker", msg->pose, msg->header);
124 geometry_msgs::Point
top[5];
136 geometry_msgs::Point bottom[5];
148 for(
int i = 0; i< 5; i++){
153 for(
int i = 0; i< 4; i++){
154 object_marker.points.push_back(top[i]);
155 object_marker.points.push_back(top[i+1]);
156 object_marker.points.push_back(bottom[i]);
157 object_marker.points.push_back(bottom[i+1]);
158 object_marker.points.push_back(top[i]);
159 object_marker.points.push_back(bottom[i]);
164 visualization_msgs::InteractiveMarker int_marker;
165 int_marker.header.frame_id =
latest_pose_.header.frame_id;
166 int_marker.name =
"marker";
167 int_marker.pose = geometry_msgs::Pose(
latest_pose_.pose);
169 visualization_msgs::Marker object_marker;
171 object_marker.type = visualization_msgs::Marker::CUBE;
179 object_marker.pose.orientation.w = 1.0;
182 object_marker.type = visualization_msgs::Marker::SPHERE;
190 object_marker.pose.orientation.w = 1.0;
193 object_marker.type = visualization_msgs::Marker::LINE_LIST;
199 object_marker.pose.orientation.w = 1.0;
203 object_marker.type = visualization_msgs::Marker::MESH_RESOURCE;
211 object_marker.pose.orientation.w = 1.0;
216 visualization_msgs::InteractiveMarkerControl object_marker_control;
217 object_marker_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
218 object_marker_control.always_visible =
true;
219 object_marker_control.markers.push_back(object_marker);
220 int_marker.controls.push_back(object_marker_control);
222 visualization_msgs::InteractiveMarkerControl control;
224 control.orientation.w = 1;
225 control.orientation.x = 1;
226 control.orientation.y = 0;
227 control.orientation.z = 0;
229 control.name =
"rotate_x";
230 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
231 int_marker.controls.push_back(control);
232 control.name =
"move_x";
233 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
234 int_marker.controls.push_back(control);
236 control.orientation.w = 1;
237 control.orientation.x = 0;
238 control.orientation.y = 1;
239 control.orientation.z = 0;
240 control.name =
"rotate_z";
241 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
242 int_marker.controls.push_back(control);
243 control.name =
"move_z";
244 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
245 int_marker.controls.push_back(control);
247 control.orientation.w = 1;
248 control.orientation.x = 0;
249 control.orientation.y = 0;
250 control.orientation.z = 1;
251 control.name =
"rotate_y";
252 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
253 int_marker.controls.push_back(control);
254 control.name =
"move_y";
255 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
256 int_marker.controls.push_back(control);
268 void publishTF(
const geometry_msgs::PoseStamped& pose) {
272 transform, pose.header.stamp,
273 pose.header.frame_id,
279 geometry_msgs::PoseStamped
pose;
280 pose.header = feedback->header;
281 pose.pose = feedback->pose;
288 void menuFeedbackCB(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
305 server_->setPose(
"marker", pose.pose, pose.header);
319 std::shared_ptr<interactive_markers::InteractiveMarkerServer>
server_;
347 int main(
int argc,
char** argv) {
ros::Subscriber pose_stamped_sub_
interactive_markers::MenuHandler menu_handler_
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
void publishTF(const geometry_msgs::PoseStamped &pose)
bool publish_pose_periodically_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void calculateBoundingBox(visualization_msgs::Marker &object_marker)
void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
interactive_markers::MenuHandler::EntryHandle circle_menu_entry_
ROSCPP_DECL const std::string & getName()
void timerPoseCallback(const ros::TimerEvent &e)
void initializeInteractiveMarker()
void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
ROSCPP_DECL void spin(Spinner &spinner)
std::shared_ptr< tf::TransformBroadcaster > tf_broadcaster_
bool setCheckState(EntryHandle handle, CheckState check_state)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
geometry_msgs::PoseStamped latest_pose_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void timerTFCallback(const ros::TimerEvent &e)
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
int main(int argc, char **argv)
bool hasParam(const std::string &key) const
void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr &msg)