example_frame_broadcaster_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018, Andreas Gustavsson.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *
34 * Author: Andreas Gustavsson
35 *********************************************************************/
36 
37 #include <ros/ros.h>
41 #include <geometry_msgs/TransformStamped.h>
42 #include <cmath>
43 
44 
45 /* Entry point */
46 int main(int argc, char** argv)
47 {
48  ros::init(argc, argv, "frame_broadcaster", ros::init_options::AnonymousName);
49  ros::NodeHandle node;
50  ros::NodeHandle node_priv("~");
51 
52  ros::Time now;
53 
55  std::vector<geometry_msgs::TransformStamped> transforms;
56  transforms.resize(4);
57  {
58  std::vector<std::string> parent_frames;
59  parent_frames.push_back("map");
60  parent_frames.push_back("odom");
61  parent_frames.push_back("base_link");
62  parent_frames.push_back("base_link");
63  std::vector<std::string> child_frames;
64  child_frames.push_back("odom");
65  child_frames.push_back("base_link");
66  child_frames.push_back("camera_link");
67  child_frames.push_back("laser");
68 
69  // Setup headers and child frames
70  for (int i = 0; i<transforms.size(); ++i)
71  {
72  transforms[i].header.frame_id = parent_frames[i];
73  transforms[i].header.seq = 0;
74  transforms[i].child_frame_id = child_frames[i];
75  }
76 
77  // Set up static properties
78  transforms[0].transform.translation.x = 0.0;
79  transforms[0].transform.translation.y = 0.0;
80  transforms[0].transform.translation.z = 0.0;
81  transforms[0].transform.rotation.x = 0.0;
82  transforms[0].transform.rotation.y = 0.0;
83  transforms[0].transform.rotation.z = 0.0;
84  transforms[0].transform.rotation.w = 1.0;
85  }
86 
87  double dx, dy, radius, dtheta;
88  node_priv.param("dx", dx, 0.0);
89  node_priv.param("dy", dy, 0.0);
90  node_priv.param("radius", radius, 0.0);
91  node_priv.param("dtheta", dtheta, 0.0);
92 
93  const double PI_HALF = M_PI/2;
94  const double TWO_PI = 2*M_PI;
95  double x = radius;
96  double y = 0.0;
97  double theta = 0.0;
98  double dxsum = 0.0;
99  double dysum = 0.0;
100 
101  // Static setup of odom <-> base_link relation
102  {
103  tf2::Quaternion q;
104  q.setRPY(0, 0, dtheta == 0.0 ? 0.0 : theta + PI_HALF);
105  transforms[1].transform.rotation.x = q.x();
106  transforms[1].transform.rotation.y = q.y();
107  transforms[1].transform.rotation.z = q.z();
108  transforms[1].transform.rotation.w = q.w();
109 
110  transforms[1].transform.translation.z = 0.0;
111  }
112 
113  // Set up camera
114  {
115  tf2::Quaternion q = tf2::Quaternion(0,0,0,1);
116  transforms[2].transform.translation.x = 0.035;
117  transforms[2].transform.translation.y = -0.025;
118  transforms[2].transform.translation.z = -0.1;
119  transforms[2].transform.rotation.x = 0.0;
120  transforms[2].transform.rotation.y = 0.0;
121  transforms[2].transform.rotation.z = 0.0;
122  transforms[2].transform.rotation.w = 1.0;
123  }
124 
125 
126  // Set up laser
127  {
128  tf2::Quaternion q;
129  q.setRPY(0.0, 0.0, 3.08923); // 177 degrees rotation around Z axis
130  transforms[3].transform.translation.x = -0.053;
131  transforms[3].transform.translation.y = -0.036;
132  transforms[3].transform.translation.z = 0.03;
133  transforms[3].transform.rotation.x = q.x();
134  transforms[3].transform.rotation.y = q.y();
135  transforms[3].transform.rotation.z = q.z();
136  transforms[3].transform.rotation.w = q.w();
137  }
138 
139  // ~Publish rate
140  ros::Rate rate(10.0);
141 
142  while (node.ok())
143  {
144 
145  now = ros::Time::now();
146 
147  for (int i = 0; i<transforms.size(); ++i)
148  {
149  transforms[i].header.stamp = now;
150  }
151 
152 
153 // // Odometry frame's location in map
154 // br.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0,0,0,1),
155 // tf::Vector3(0,0,0)),
156 // now,
157 // "map",
158 // "odom"));
159 
160  // Robot in odometry frame
161  transforms[1].transform.translation.x = x;
162  transforms[1].transform.translation.y = y;
163 
164 // br.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(tf::Vector3(0,0,1),
165 // dtheta == 0 ? 0.0 : theta + PI_HALF),
166 // tf::Vector3(x,y,0)),
167 // now,
168 // "odom",
169 // "base_link"));
170 
171  theta += dtheta;
172  x = radius * cos(theta);
173  y = radius * sin(theta);
174  dxsum+=dx;
175  dysum+=dy;
176  x+=dxsum;
177  y+=dysum;
178 
179 // // Camera position on robot
180 // br.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0,0,0,1),
181 // tf::Vector3(0.035,-0.025,-0.1)),
182 // now,
183 // "base_link",
184 // "camera_link"));
185 
186 // // Lidar position on robot
187 // br.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(tf::Vector3(0.0, 0.0, 1.0),
188 // 3.08923), // 177 degrees
189 // tf::Vector3(-0.053,-0.036,0.03)),
190 // now,
191 // "base_link",
192 // "laser"));
193 
194  // Publish transforms
195  br.sendTransform(transforms);
196 
197  rate.sleep();
198  }
199  return 0;
200 }
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void sendTransform(const geometry_msgs::TransformStamped &transform)
bool sleep()
static Time now()
bool ok() const
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)


find_moving_objects
Author(s): Andreas Gustavsson
autogenerated on Mon Jun 10 2019 13:13:19