33 #include <geometry_msgs/Twist.h>    34 #include <geometry_msgs/Pose.h>    43       : nh(
"~"), 
server(
"turtlebot_marker_server")
    45       std::string cmd_vel_topic;
    47       nh.param<std::string>(
"link_name", link_name, 
"/base_link");
    48       nh.param<
double>(
"linear_scale", linear_scale, 1.0);
    49       nh.param<
double>(
"angular_scale", angular_scale, 2.2);
    51       vel_pub = nh.advertise<geometry_msgs::Twist>(
"/cmd_vel", 1);
    52       createInteractiveMarkers();
    54       ROS_INFO(
"[turtlebot_marker_server] Initialized.");
    58         const InteractiveMarkerFeedbackConstPtr &feedback );
    61     void createInteractiveMarkers();
    74     const InteractiveMarkerFeedbackConstPtr &feedback )
    79   geometry_msgs::Twist vel;
    80   vel.angular.z = angular_scale*yaw;
    81   vel.linear.x = linear_scale*feedback->pose.position.x;
    86   server.setPose(
"turtlebot_marker", geometry_msgs::Pose());
    94   InteractiveMarker int_marker;
    95   int_marker.header.frame_id = link_name;
    96   int_marker.name = 
"turtlebot_marker";
    99   InteractiveMarkerControl 
control;
   101   control.orientation_mode = InteractiveMarkerControl::FIXED;
   102   control.orientation.w = 1;
   103   control.orientation.x = 1;
   104   control.orientation.y = 0;
   105   control.orientation.z = 0;
   106   control.name = 
"move_x";
   107   control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
   108   int_marker.controls.push_back(control);
   110   control.orientation.w = 1;
   111   control.orientation.x = 0;
   112   control.orientation.y = 1;
   113   control.orientation.z = 0;
   114   control.name = 
"rotate_z";
   116   control.interaction_mode = InteractiveMarkerControl::MOVE_ROTATE;
   118   int_marker.controls.push_back(control);
   135 int main(
int argc, 
char** argv)
   137   ros::init(argc, argv, 
"turtlebot_marker_server");
 void processFeedback(const InteractiveMarkerFeedbackConstPtr &feedback)
static double getYaw(const Quaternion &bt_q)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
ROSCPP_DECL void spin(Spinner &spinner)
void createInteractiveMarkers()
int main(int argc, char **argv)
interactive_markers::InteractiveMarkerServer server