trajectory_recorder.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 <ros/ros.h>
39 
40 #include <geometry_msgs/Twist.h>
41 #include <nav_msgs/Path.h>
44 
45 #include <math.h>
46 #include <string>
47 
49 
51 {
52 public:
53  RecorderNode();
54  ~RecorderNode();
55  void spin();
56 
57 private:
58  std::string topic_path_;
59  std::string frame_robot_;
60  std::string frame_global_;
62  double ang_interval_;
64 
70 
71  nav_msgs::Path path_;
72 };
73 
75  : nh_()
76  , pnh_("~")
77  , tfl_(tfbuf_)
78 {
80  pnh_.param("frame_robot", frame_robot_, std::string("base_link"));
81  pnh_.param("frame_global", frame_global_, std::string("map"));
82  neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("recpath"));
83  pnh_.param("dist_interval", dist_interval_, 0.3);
84  pnh_.param("ang_interval", ang_interval_, 1.0);
85  pnh_.param("store_time", store_time_, false);
86 
87  pub_path_ = neonavigation_common::compat::advertise<nav_msgs::Path>(
88  nh_, "path",
89  pnh_, topic_path_, 10, true);
90 }
92 {
93 }
94 
95 float dist2d(geometry_msgs::Point& a, geometry_msgs::Point& b)
96 {
97  return sqrtf(powf(a.x - b.x, 2) + powf(a.y - b.y, 2));
98 }
99 
101 {
102  ros::Rate loop_rate(50);
103  path_.header.frame_id = frame_global_;
104  path_.header.seq = 0;
105 
106  while (ros::ok())
107  {
108  ros::Time now = ros::Time(0);
109  if (store_time_)
110  now = ros::Time::now();
112  try
113  {
114  tf2::fromMsg(
116  }
117  catch (tf2::TransformException& e)
118  {
119  ROS_WARN("TF exception: %s", e.what());
120  continue;
121  }
122  geometry_msgs::PoseStamped pose;
123  tf2::Quaternion q;
124  transform.getBasis().getRotation(q);
125  pose.pose.orientation = tf2::toMsg(q);
126  tf2::Vector3 origin = transform.getOrigin();
127  pose.pose.position.x = origin.x();
128  pose.pose.position.y = origin.y();
129  pose.pose.position.z = origin.z();
130  pose.header.frame_id = frame_global_;
131  pose.header.stamp = now;
132  pose.header.seq = path_.poses.size();
133 
134  path_.header.seq++;
135  path_.header.stamp = now;
136 
137  if (path_.poses.size() == 0)
138  {
139  path_.poses.push_back(pose);
141  }
142  else if (dist2d(path_.poses.back().pose.position, pose.pose.position) > dist_interval_)
143  {
144  path_.poses.push_back(pose);
146  }
147 
148  ros::spinOnce();
149  loop_rate.sleep();
150  }
151 }
152 
153 int main(int argc, char** argv)
154 {
155  ros::init(argc, argv, "trajectory_recorder");
156 
157  RecorderNode rec;
158  rec.spin();
159 
160  return 0;
161 }
float dist2d(geometry_msgs::Point &a, geometry_msgs::Point &b)
void publish(const boost::shared_ptr< M > &message) const
std::string frame_robot_
std::string topic_path_
int main(int argc, char **argv)
ros::Publisher pub_path_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
tf2_ros::Buffer tfbuf_
std::string frame_global_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void fromMsg(const A &, B &b)
ROSCPP_DECL bool ok()
ros::NodeHandle pnh_
bool sleep()
B toMsg(const A &a)
static Time now()
ros::NodeHandle nh_
ROSCPP_DECL void spinOnce()
nav_msgs::Path path_
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
tf2_ros::TransformListener tfl_


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:09