00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <stdio.h>
00028 #include <vector>
00029 #include <math.h>
00030 #include <visualization_msgs/Marker.h>
00031 #include <visualization_msgs/MarkerArray.h>
00032 #include <numeric>
00033 #include <interactive_markers/interactive_marker_server.h>
00034 #include <interactive_markers/menu_handler.h>
00035 #include <boost/lexical_cast.hpp>
00036 #include <boost/format.hpp>
00037 #include "std_msgs/String.h"
00038 #include <trajectory_planner/coordinates.h>
00039
00040
00041 using namespace visualization_msgs;
00042
00043
00044 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
00045 ros::NodeHandle* p_n;
00046 ros::Publisher coor_pub;
00047 trajectory_planner::coordinates message;
00048
00049
00050
00051 void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00052 {
00053 if( feedback->mouse_point_valid )
00054 {
00055
00056
00057
00058
00059 }
00060
00061 switch ( feedback->event_type )
00062 {
00063 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
00064 message.x=feedback->pose.position.x; message.y=feedback->pose.position.y; message.theta=2.0*asin(feedback->pose.orientation.z);
00065
00066 message.header.stamp = ros::Time::now();
00067 message.header.frame_id = "/world";
00068
00069 coor_pub.publish(message);
00070
00071 break;
00072 }
00073
00074 server->applyChanges();
00075 }
00076
00077
00078 Marker makeBox( InteractiveMarker &msg )
00079 {
00080 Marker marker;
00081
00082 marker.type = Marker::ARROW;
00083 marker.scale.x = msg.scale;
00084 marker.scale.y = msg.scale;
00085 marker.scale.z = msg.scale;
00086 marker.color.r = 0;
00087 marker.color.g = 0.7;
00088 marker.color.b = 0;
00089 marker.color.a = 0.6;
00090 return marker;
00091 }
00092
00093
00094 InteractiveMarkerControl& makeBoxControl( InteractiveMarker &msg )
00095 {
00096 InteractiveMarkerControl control;
00097 control.always_visible = true;
00098 control.markers.push_back( makeBox(msg) );
00099 msg.controls.push_back( control );
00100
00101 return msg.controls.back();
00102 }
00103
00104
00105 void make6DofMarker( bool fixed )
00106 {
00107 InteractiveMarker int_marker;
00108 int_marker.header.frame_id = "/world";
00109 int_marker.pose.position.x = 0;
00110 int_marker.pose.position.y = 0;
00111 int_marker.pose.position.z = 0;
00112 int_marker.scale = 0.4;
00113
00114 int_marker.name = "Control target";
00115 int_marker.description = "Control the final \nposition of the robot";
00116
00117
00118 makeBoxControl(int_marker);
00119 InteractiveMarkerControl control;
00120
00121 control.orientation.w = 1;
00122 control.orientation.x = 1;
00123 control.orientation.y = 0;
00124 control.orientation.z = 0;
00125 control.name = "move_x";
00126 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00127 int_marker.controls.push_back(control);
00128
00129 control.orientation.w = 1;
00130 control.orientation.x = 0;
00131 control.orientation.y = 0;
00132 control.orientation.z = 1;
00133 control.name = "move_y";
00134 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00135 int_marker.controls.push_back(control);
00136
00137 control.orientation.w = 1;
00138 control.orientation.x = 0;
00139 control.orientation.y = 1;
00140 control.orientation.z = 0;
00141 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
00142 control.name = "rotate_z";
00143 int_marker.controls.push_back(control);
00144
00145 server->insert(int_marker);
00146 server->setCallback(int_marker.name, &processFeedback);
00147 }
00148
00149
00150 int main(int argc, char **argv)
00151 {
00152 ros::init(argc, argv, "APgenerator");
00153 ros::NodeHandle n("~");
00154 ros::Rate loop_rate(10);
00155 p_n=&n;
00156
00157 coor_pub = n.advertise<trajectory_planner::coordinates>("/msg_coordinates", 1000);
00158
00159
00160 server.reset( new interactive_markers::InteractiveMarkerServer("APgenerator/im","",false) );
00161 make6DofMarker( true );
00162 server->applyChanges();
00163
00164 while(ros::ok())
00165 {
00166
00167
00168
00169 loop_rate.sleep();
00170 ros::spinOnce();
00171 }
00172
00173 server.reset();
00174 }