41 #include <geometry_msgs/TransformStamped.h> 46 int main(
int argc,
char** argv)
55 std::vector<geometry_msgs::TransformStamped> transforms;
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");
70 for (
int i = 0; i<transforms.size(); ++i)
72 transforms[i].header.frame_id = parent_frames[i];
73 transforms[i].header.seq = 0;
74 transforms[i].child_frame_id = child_frames[i];
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;
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);
93 const double PI_HALF = M_PI/2;
94 const double TWO_PI = 2*M_PI;
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();
110 transforms[1].transform.translation.z = 0.0;
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;
129 q.
setRPY(0.0, 0.0, 3.08923);
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();
147 for (
int i = 0; i<transforms.size(); ++i)
149 transforms[i].header.stamp = now;
161 transforms[1].transform.translation.x = x;
162 transforms[1].transform.translation.y = y;
172 x = radius *
cos(theta);
173 y = radius *
sin(theta);
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 ¶m_name, T ¶m_val, const T &default_val) 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)