turtle_tf2_listener.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <geometry_msgs/TransformStamped.h>
4 #include <geometry_msgs/Twist.h>
5 #include <turtlesim/Spawn.h>
6 
7 int main(int argc, char** argv){
8  ros::init(argc, argv, "my_tf2_listener");
9 
10  ros::NodeHandle node;
11 
14  node.serviceClient<turtlesim::Spawn>("spawn");
15  turtlesim::Spawn turtle;
16  turtle.request.x = 4;
17  turtle.request.y = 2;
18  turtle.request.theta = 0;
19  turtle.request.name = "turtle2";
20  spawner.call(turtle);
21 
23  node.advertise<geometry_msgs::Twist>("turtle2/cmd_vel", 10);
24 
26  tf2_ros::TransformListener tfListener(tfBuffer);
27 
28  ros::Rate rate(10.0);
29  while (node.ok()){
30  geometry_msgs::TransformStamped transformStamped;
31  try{
32  transformStamped = tfBuffer.lookupTransform("turtle2", "turtle1",
33  ros::Time(0));
34  }
35  catch (tf2::TransformException &ex) {
36  ROS_WARN("%s",ex.what());
37  ros::Duration(1.0).sleep();
38  continue;
39  }
40 
41  geometry_msgs::Twist vel_msg;
42 
43  vel_msg.angular.z = 4.0 * atan2(transformStamped.transform.translation.y,
44  transformStamped.transform.translation.x);
45  vel_msg.linear.x = 0.5 * sqrt(pow(transformStamped.transform.translation.x, 2) +
46  pow(transformStamped.transform.translation.y, 2));
47  turtle_vel.publish(vel_msg);
48 
49  rate.sleep();
50  }
51  return 0;
52 };
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish(const boost::shared_ptr< M > &message) const
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
#define ROS_WARN(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool sleep()
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
bool ok() const
int main(int argc, char **argv)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


turtle_tf2
Author(s): Denis Štogl
autogenerated on Mon Jun 10 2019 13:24:50