Go to the documentation of this file.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
00028
00029
00030 #include <ros/ros.h>
00031 #include <interactive_markers/interactive_marker_server.h>
00032 #include <string.h>
00033 #include <geometry_msgs/Twist.h>
00034 #include <geometry_msgs/Pose.h>
00035 #include <tf/tf.h>
00036
00037 using namespace visualization_msgs;
00038
00039 class MarkerServer
00040 {
00041 public:
00042 MarkerServer()
00043 : nh("~"), server("twist_marker_server")
00044 {
00045 std::string cmd_vel_topic;
00046
00047 nh.param<std::string>("link_name", link_name, "/base_link");
00048 nh.param<std::string>("robot_name", robot_name, "robot");
00049 nh.param<double>("linear_scale", linear_drive_scale, 1.0);
00050 nh.param<double>("angular_scale", angular_drive_scale, 2.2);
00051 nh.param<double>("marker_size_scale", marker_size_scale, 1.0);
00052
00053 vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
00054 createInteractiveMarkers();
00055
00056 ROS_INFO("[twist_marker_server] Initialized.");
00057 }
00058
00059 void processFeedback(
00060 const InteractiveMarkerFeedbackConstPtr &feedback );
00061
00062 private:
00063 void createInteractiveMarkers();
00064
00065 ros::NodeHandle nh;
00066 ros::Publisher vel_pub;
00067 interactive_markers::InteractiveMarkerServer server;
00068
00069 double linear_drive_scale;
00070 double angular_drive_scale;
00071
00072 double marker_size_scale;
00073
00074 std::string link_name;
00075 std::string robot_name;
00076 };
00077
00078 void MarkerServer::processFeedback(
00079 const InteractiveMarkerFeedbackConstPtr &feedback )
00080 {
00081
00082 double yaw = tf::getYaw(feedback->pose.orientation);
00083
00084 geometry_msgs::Twist vel;
00085 vel.angular.z = angular_drive_scale * yaw;
00086 vel.linear.x = linear_drive_scale * feedback->pose.position.x;
00087
00088 vel_pub.publish(vel);
00089
00090
00091 server.setPose(robot_name + "_twist_marker", geometry_msgs::Pose());
00092
00093 server.applyChanges();
00094 }
00095
00096 void MarkerServer::createInteractiveMarkers()
00097 {
00098
00099 InteractiveMarker int_marker;
00100 int_marker.header.frame_id = link_name;
00101 int_marker.name = robot_name + "_twist_marker";
00102 int_marker.description = "twist controller for " + robot_name;
00103 int_marker.scale = marker_size_scale;
00104
00105 InteractiveMarkerControl control;
00106
00107 control.orientation_mode = InteractiveMarkerControl::FIXED;
00108 control.orientation.w = 1;
00109 control.orientation.x = 1;
00110 control.orientation.y = 0;
00111 control.orientation.z = 0;
00112 control.name = "move_x";
00113 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00114 int_marker.controls.push_back(control);
00115
00116 control.orientation.w = 1;
00117 control.orientation.x = 0;
00118 control.orientation.y = 1;
00119 control.orientation.z = 0;
00120 control.name = "rotate_z";
00121
00122 control.interaction_mode = InteractiveMarkerControl::MOVE_ROTATE;
00123
00124 int_marker.controls.push_back(control);
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135 server.insert(int_marker, boost::bind( &MarkerServer::processFeedback, this, _1 ));
00136
00137 server.applyChanges();
00138 }
00139
00140
00141 int main(int argc, char** argv)
00142 {
00143 ros::init(argc, argv, "marker_server");
00144 MarkerServer server;
00145
00146 ros::spin();
00147 }