dummy_robot.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
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 #include <ros/ros.h>
31 #include <geometry_msgs/Twist.h>
32 #include <geometry_msgs/PoseWithCovarianceStamped.h>
33 #include <nav_msgs/Odometry.h>
34 #include <tf2/utils.h>
38 
40 
42 {
43 protected:
46 
47  double x_;
48  double y_;
49  double yaw_;
50  float v_;
51  float w_;
52 
59 
60  void cbTwist(const geometry_msgs::Twist::ConstPtr& msg)
61  {
62  v_ = msg->linear.x;
63  w_ = msg->angular.z;
64  }
65  void cbInit(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
66  {
67  geometry_msgs::PoseStamped pose_in, pose_out;
68  pose_in.header = msg->header;
69  pose_in.pose = msg->pose.pose;
70  try
71  {
72  geometry_msgs::TransformStamped trans =
73  tfbuf_.lookupTransform("odom", pose_in.header.frame_id, pose_in.header.stamp, ros::Duration(1.0));
74  tf2::doTransform(pose_in, pose_out, trans);
75  }
76  catch (tf2::TransformException& e)
77  {
78  ROS_WARN("%s", e.what());
79  return;
80  }
81 
82  x_ = pose_out.pose.position.x;
83  y_ = pose_out.pose.position.y;
84  yaw_ = tf2::getYaw(pose_out.pose.orientation);
85  v_ = 0;
86  w_ = 0;
87  }
88 
89 public:
91  : nh_()
92  , pnh_("~")
93  , tfl_(tfbuf_)
94  {
96  pnh_.param("initial_x", x_, 0.0);
97  pnh_.param("initial_y", y_, 0.0);
98  pnh_.param("initial_yaw", yaw_, 0.0);
99  v_ = 0.0;
100  w_ = 0.0;
101 
102  pub_odom_ = nh_.advertise<nav_msgs::Odometry>("odom", 1, true);
103  sub_twist_ = nh_.subscribe("cmd_vel", 1, &DummyRobotNode::cbTwist, this);
104  sub_init_ = nh_.subscribe("initialpose", 1, &DummyRobotNode::cbInit, this);
105  }
106  void spin()
107  {
108  const float dt = 0.01;
109  ros::Rate rate(1.0 / dt);
110 
111  while (ros::ok())
112  {
113  ros::spinOnce();
114  rate.sleep();
115  const ros::Time current_time = ros::Time::now();
116 
117  yaw_ += w_ * dt;
118  x_ += cosf(yaw_) * v_ * dt;
119  y_ += sinf(yaw_) * v_ * dt;
120 
121  geometry_msgs::TransformStamped trans;
122  trans.header.stamp = current_time;
123  trans.header.frame_id = "odom";
124  trans.child_frame_id = "base_link";
125  trans.transform.translation = tf2::toMsg(tf2::Vector3(x_, y_, 0.0));
126  trans.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw_));
127  tfb_.sendTransform(trans);
128 
129  nav_msgs::Odometry odom;
130  odom.header.frame_id = "odom";
131  odom.header.stamp = current_time;
132  odom.child_frame_id = "base_link";
133  odom.pose.pose.position.x = x_;
134  odom.pose.pose.position.y = y_;
135  odom.pose.pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw_));
136  odom.twist.twist.linear.x = v_;
137  odom.twist.twist.angular.z = w_;
138  pub_odom_.publish(odom);
139  }
140  }
141 };
142 
143 int main(int argc, char* argv[])
144 {
145  ros::init(argc, argv, "dummy_robot");
146 
147  DummyRobotNode robot;
148  robot.spin();
149 
150  return 0;
151 }
tf2_ros::TransformListener tfl_
Definition: dummy_robot.cpp:58
void cbInit(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: dummy_robot.cpp:65
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char *argv[])
ros::NodeHandle pnh_
Definition: dummy_robot.cpp:45
tf2_ros::TransformBroadcaster tfb_
Definition: dummy_robot.cpp:57
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
void cbTwist(const geometry_msgs::Twist::ConstPtr &msg)
Definition: dummy_robot.cpp:60
ros::Publisher pub_odom_
Definition: dummy_robot.cpp:53
#define ROS_WARN(...)
ros::Subscriber sub_twist_
Definition: dummy_robot.cpp:54
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle nh_
Definition: dummy_robot.cpp:44
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sendTransform(const geometry_msgs::TransformStamped &transform)
bool sleep()
double getYaw(const A &a)
B toMsg(const A &a)
tf2_ros::Buffer tfbuf_
Definition: dummy_robot.cpp:56
static Time now()
ROSCPP_DECL void spinOnce()
ros::Subscriber sub_init_
Definition: dummy_robot.cpp:55


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06