trajectory_server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, ATR, Atsushi Watanabe
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * This research was supported by a contract with the Ministry of Internal
32  Affairs and Communications entitled, 'Novel and innovative R&D making use
33  of brain structures'
34 
35  This software was implemented to accomplish the above research.
36  */
37 
38 #include <cmath>
39 #include <fstream>
40 #include <string>
41 
42 #include <ros/ros.h>
43 
44 #include <geometry_msgs/Twist.h>
46 #include <nav_msgs/Path.h>
48 #include <trajectory_tracker_msgs/ChangePath.h>
49 #include <trajectory_tracker_msgs/TrajectoryServerStatus.h>
50 #include <visualization_msgs/InteractiveMarkerUpdate.h>
51 
53 
55 
57 {
58 public:
59  ServerNode();
60  ~ServerNode();
61  void spin();
62 
63 private:
70 
71  nav_msgs::Path path_;
72  std::string topic_path_;
73  trajectory_tracker_msgs::ChangePath::Request req_path_;
74  double hz_;
77  double filter_step_;
79 
80  bool loadFile();
81  void loadPath();
82  bool change(trajectory_tracker_msgs::ChangePath::Request& req,
83  trajectory_tracker_msgs::ChangePath::Response& res);
84  void processFeedback(
85  const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
86  void updateIM();
87  enum
88  {
91  };
94 };
95 
97  : nh_()
98  , pnh_("~")
99  , srv_im_fb_("trajectory_server")
100  , buffer_(new uint8_t[1024])
101 {
103  neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("path"));
104  pnh_.param("file", req_path_.filename, std::string("a.path"));
105  pnh_.param("hz", hz_, 5.0);
106  pnh_.param("filter_step", filter_step_, 0.0);
107 
108  pub_path_ = neonavigation_common::compat::advertise<nav_msgs::Path>(
109  nh_, "path",
110  pnh_, topic_path_, 2, true);
111  pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryServerStatus>("status", 2);
113  nh_, "change_path",
114  pnh_, "ChangePath", &ServerNode::change, this);
115  update_num_ = 0;
116  max_markers_ = 0;
117 }
119 {
120 }
121 
123 {
124  std::ifstream ifs(req_path_.filename.c_str());
125  if (ifs.good())
126  {
127  ifs.seekg(0, ifs.end);
128  serial_size_ = ifs.tellg();
129  ifs.seekg(0, ifs.beg);
130  buffer_.reset(new uint8_t[serial_size_]);
131  ifs.read(reinterpret_cast<char*>(buffer_.get()), serial_size_);
132 
133  return true;
134  }
135  return false;
136 }
137 
139  const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
140 {
141  int id = std::atoi(feedback->marker_name.c_str());
142  switch (feedback->event_type)
143  {
144  case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
145  path_.poses[id].pose = feedback->pose;
146  break;
147  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
148  path_.header.stamp = ros::Time::now();
150  break;
151  case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT:
152  switch (feedback->menu_entry_id)
153  {
154  case MENU_DELETE:
155  path_.poses.erase(path_.poses.begin() + id);
156  break;
157  case MENU_ADD:
158  path_.poses.insert(path_.poses.begin() + id, path_.poses[id]);
159  break;
160  }
162  updateIM();
163  break;
164  }
165 }
166 
168 {
169  visualization_msgs::InteractiveMarkerUpdate viz;
170  viz.type = viz.KEEP_ALIVE;
171  viz.seq_num = update_num_++;
172  viz.server_id = "Path";
173  srv_im_fb_.clear();
174  int i = 0;
175  for (auto& p : path_.poses)
176  {
177  visualization_msgs::InteractiveMarker mark;
178  visualization_msgs::Marker marker;
179  visualization_msgs::InteractiveMarkerControl ctl;
180  visualization_msgs::MenuEntry menu;
181  mark.header = path_.header;
182  mark.pose = p.pose;
183  mark.scale = 1.0;
184  std::stringstream ss;
185  ss << i++;
186  mark.name = ss.str();
187  marker.ns = "Path";
188  marker.id = i;
189  marker.scale.x = 0.2;
190  marker.scale.y = 0.05;
191  marker.scale.z = 0.05;
192  marker.color.r = 1;
193  marker.color.g = 1;
194  marker.color.b = 1;
195  marker.color.a = 1;
196  marker.type = marker.ARROW;
197 
198  ss << " ctl";
199  ctl.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 1.0, 0.0), M_PI / 2.0));
200  ctl.interaction_mode = ctl.MOVE_ROTATE;
201  ctl.orientation_mode = ctl.INHERIT;
202  ctl.always_visible = true;
203  ctl.markers.push_back(marker);
204  ctl.name = ss.str();
205  mark.controls.push_back(ctl);
206 
207  ss << " menu";
208  ctl.interaction_mode = ctl.MENU;
209  ctl.name = ss.str();
210  marker.type = marker.SPHERE;
211  marker.color.g = 0;
212  marker.color.b = 0;
213  marker.scale.x = 0.08;
214  marker.scale.y = 0.08;
215  marker.scale.z = 0.08;
216  ctl.markers[0] = marker;
217  mark.controls.push_back(ctl);
218 
219  menu.id = MENU_DELETE;
220  menu.parent_id = 0;
221  menu.title = "Delete";
222  menu.command_type = menu.FEEDBACK;
223  mark.menu_entries.push_back(menu);
224  menu.id = MENU_ADD;
225  menu.parent_id = 0;
226  menu.title = "Add";
227 
228  mark.menu_entries.push_back(menu);
229  srv_im_fb_.insert(mark, boost::bind(&ServerNode::processFeedback, this, _1));
230  viz.markers.push_back(mark);
231  }
233 }
234 
235 bool ServerNode::change(trajectory_tracker_msgs::ChangePath::Request& req,
236  trajectory_tracker_msgs::ChangePath::Response& res)
237 {
238  req_path_ = req;
239  res.success = false;
240 
241  if (loadFile())
242  {
243  res.success = true;
246  path_.header.stamp = ros::Time::now();
247  if (filter_step_ > 0)
248  {
249  std::cout << filter_step_ << std::endl;
251  trajectory_tracker::Filter::FILTER_LPF, filter_step_, path_.poses[0].pose.position.x);
253  trajectory_tracker::Filter::FILTER_LPF, filter_step_, path_.poses[0].pose.position.y);
254 
255  for (size_t i = 0; i < path_.poses.size(); i++)
256  {
257  path_.poses[i].pose.position.x = lpf_[0]->in(path_.poses[i].pose.position.x);
258  path_.poses[i].pose.position.y = lpf_[1]->in(path_.poses[i].pose.position.y);
259  }
260 
261  delete lpf_[0];
262  delete lpf_[1];
263  }
264 
266  updateIM();
267  }
268  else
269  {
270  serial_size_ = 0;
271  req_path_.filename = "";
272  path_.poses.clear();
273  path_.header.frame_id = "map";
274  }
275  return true;
276 }
277 
279 {
280  ros::Rate loop_rate(hz_);
281  trajectory_tracker_msgs::TrajectoryServerStatus status;
282 
283  while (ros::ok())
284  {
285  status.header = path_.header;
286  status.filename = req_path_.filename;
287  status.id = req_path_.id;
288  pub_status_.publish(status);
289  ros::spinOnce();
290  loop_rate.sleep();
291  }
292 }
293 
294 int main(int argc, char** argv)
295 {
296  ros::init(argc, argv, "trajectory_server");
297 
298  ServerNode serv;
299  serv.spin();
300 
301  return 0;
302 }
ros::Publisher pub_path_
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool change(trajectory_tracker_msgs::ChangePath::Request &req, trajectory_tracker_msgs::ChangePath::Response &res)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ros::ServiceServer srv_change_path_
void loadPath()
ros::ServiceServer advertiseService(ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
boost::shared_array< uint8_t > buffer_
ros::NodeHandle pnh_
nav_msgs::Path path_
bool sleep()
std::string topic_path_
B toMsg(const A &a)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
ros::NodeHandle nh_
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
interactive_markers::InteractiveMarkerServer srv_im_fb_
trajectory_tracker::Filter * lpf_[2]
static Time now()
INTERACTIVE_MARKERS_PUBLIC void clear()
ros::Publisher pub_status_
trajectory_tracker_msgs::ChangePath::Request req_path_
ROSCPP_DECL void spinOnce()
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
void deserialize(Stream &stream, T &t)
float in(const float &i)
Definition: filter.h:85


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:40