marker_server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * (c) 2013, Mike Purvis
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
32 #include <geometry_msgs/Twist.h>
33 #include <geometry_msgs/Pose.h>
34 #include <ros/ros.h>
35 #include <tf/tf.h>
36 
37 #include <algorithm>
38 #include <string>
39 #include <map>
40 
41 using visualization_msgs::InteractiveMarker;
42 using visualization_msgs::InteractiveMarkerControl;
43 using visualization_msgs::InteractiveMarkerFeedback;
44 
46 {
47  public:
49  : nh("~"), server("twist_marker_server")
50  {
51  std::string cmd_vel_topic;
52 
53  nh.param<std::string>("link_name", link_name, "/base_link");
54  nh.param<std::string>("robot_name", robot_name, "robot");
55 
56  if (nh.getParam("linear_scale", linear_drive_scale_map))
57  {
58  nh.getParam("linear_scale", linear_drive_scale_map);
59  nh.getParam("max_positive_linear_velocity", max_positive_linear_velocity_map);
60  nh.getParam("max_negative_linear_velocity", max_negative_linear_velocity_map);
61  }
62  else
63  {
64  nh.param<double>("linear_scale", linear_drive_scale_map["x"], 1.0);
65  nh.param<double>("max_positive_linear_velocity", max_positive_linear_velocity_map["x"], 1.0);
66  nh.param<double>("max_negative_linear_velocity", max_negative_linear_velocity_map["x"], -1.0);
67  }
68 
69  nh.param<double>("angular_scale", angular_drive_scale, 2.2);
70  nh.param<double>("max_angular_velocity", max_angular_velocity, 2.2);
71  nh.param<double>("marker_size_scale", marker_size_scale, 1.0);
72 
73  vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
75 
76  ROS_INFO("[twist_marker_server] Initialized.");
77  }
78 
79  void processFeedback(
80  const InteractiveMarkerFeedback::ConstPtr &feedback);
81 
82  private:
84 
88 
89  std::map<std::string, double> linear_drive_scale_map;
90  std::map<std::string, double> max_positive_linear_velocity_map;
91  std::map<std::string, double> max_negative_linear_velocity_map;
92 
96 
97  std::string link_name;
98  std::string robot_name;
99 };
100 
102  const InteractiveMarkerFeedback::ConstPtr &feedback )
103 {
104  geometry_msgs::Twist vel;
105 
106  // Handle angular change (yaw is the only direction in which you can rotate)
107  double yaw = tf::getYaw(feedback->pose.orientation);
108  vel.angular.z = angular_drive_scale * yaw;
109  vel.angular.z = std::min(vel.angular.z, max_angular_velocity);
110  vel.angular.z = std::max(vel.angular.z, -max_angular_velocity);
111 
112  if (linear_drive_scale_map.find("x") != linear_drive_scale_map.end())
113  {
114  vel.linear.x = linear_drive_scale_map["x"] * feedback->pose.position.x;
115  vel.linear.x = std::min(vel.linear.x, max_positive_linear_velocity_map["x"]);
116  vel.linear.x = std::max(vel.linear.x, max_negative_linear_velocity_map["x"]);
117  }
118  if (linear_drive_scale_map.find("y") != linear_drive_scale_map.end())
119  {
120  vel.linear.y = linear_drive_scale_map["y"] * feedback->pose.position.y;
121  vel.linear.y = std::min(vel.linear.y, max_positive_linear_velocity_map["y"]);
122  vel.linear.y = std::max(vel.linear.y, max_negative_linear_velocity_map["y"]);
123  }
124  if (linear_drive_scale_map.find("z") != linear_drive_scale_map.end())
125  {
126  vel.linear.z = linear_drive_scale_map["z"] * feedback->pose.position.z;
127  vel.linear.z = std::min(vel.linear.z, max_positive_linear_velocity_map["z"]);
128  vel.linear.z = std::max(vel.linear.z, max_negative_linear_velocity_map["z"]);
129  }
130 
131  vel_pub.publish(vel);
132 
133  // Make the marker snap back to robot
134  server.setPose(robot_name + "_twist_marker", geometry_msgs::Pose());
135 
137 }
138 
140 {
141  // create an interactive marker for our server
142  InteractiveMarker int_marker;
143  int_marker.header.frame_id = link_name;
144  int_marker.name = robot_name + "_twist_marker";
145  int_marker.description = "twist controller for " + robot_name;
146  int_marker.scale = marker_size_scale;
147 
148  InteractiveMarkerControl control;
149 
150  control.orientation_mode = InteractiveMarkerControl::FIXED;
151 
152  if (linear_drive_scale_map.find("x") != linear_drive_scale_map.end())
153  {
154  control.orientation.w = 1;
155  control.orientation.x = 1;
156  control.orientation.y = 0;
157  control.orientation.z = 0;
158  control.name = "move_x";
159  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
160  int_marker.controls.push_back(control);
161  }
162  if (linear_drive_scale_map.find("y") != linear_drive_scale_map.end())
163  {
164  control.orientation.w = 1;
165  control.orientation.x = 0;
166  control.orientation.y = 0;
167  control.orientation.z = 1;
168  control.name = "move_y";
169  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
170  int_marker.controls.push_back(control);
171  }
172  if (linear_drive_scale_map.find("z") != linear_drive_scale_map.end())
173  {
174  control.orientation.w = 1;
175  control.orientation.x = 0;
176  control.orientation.y = 1;
177  control.orientation.z = 0;
178  control.name = "move_z";
179  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
180  int_marker.controls.push_back(control);
181  }
182 
183  control.orientation.w = 1;
184  control.orientation.x = 0;
185  control.orientation.y = 1;
186  control.orientation.z = 0;
187  control.name = "rotate_z";
188  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
189  int_marker.controls.push_back(control);
190 
191 
192 
193  server.insert(int_marker, boost::bind(&MarkerServer::processFeedback, this, _1));
194 
196 }
197 
198 
199 int main(int argc, char** argv)
200 {
201  ros::init(argc, argv, "marker_server");
203 
204  ros::spin();
205 }
ros::NodeHandle nh
void publish(const boost::shared_ptr< M > &message) const
double marker_size_scale
static double getYaw(const Quaternion &bt_q)
std::string robot_name
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher vel_pub
interactive_markers::InteractiveMarkerServer server
double max_angular_velocity
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::map< std::string, double > linear_drive_scale_map
void processFeedback(const InteractiveMarkerFeedback::ConstPtr &feedback)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::map< std::string, double > max_negative_linear_velocity_map
void createInteractiveMarkers()
void insert(const visualization_msgs::InteractiveMarker &int_marker)
int main(int argc, char **argv)
double angular_drive_scale
bool getParam(const std::string &key, std::string &s) const
bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
std::string link_name
std::map< std::string, double > max_positive_linear_velocity_map


interactive_marker_twist_server
Author(s):
autogenerated on Wed Jun 5 2019 21:51:16