turtle_tf_listener.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <geometry_msgs/Twist.h>
4 #include <turtlesim/Spawn.h>
5 
6 int main(int argc, char** argv){
7  ros::init(argc, argv, "my_tf_listener");
8 
9  ros::NodeHandle node;
10 
12  ros::ServiceClient add_turtle =
13  node.serviceClient<turtlesim::Spawn>("spawn");
14  turtlesim::Spawn srv;
15  add_turtle.call(srv);
16 
18  node.advertise<geometry_msgs::Twist>("turtle2/cmd_vel", 10);
19 
21 
22  ros::Rate rate(10.0);
23  while (node.ok()){
24  tf::StampedTransform transform;
25  try{
26  listener.lookupTransform("/turtle2", "/turtle1",
27  ros::Time(0), transform);
28  }
29  catch (tf::TransformException &ex) {
30  ROS_ERROR("%s",ex.what());
31  ros::Duration(1.0).sleep();
32  continue;
33  }
34 
35  geometry_msgs::Twist vel_msg;
36  vel_msg.angular.z = 4.0 * atan2(transform.getOrigin().y(),
37  transform.getOrigin().x());
38  vel_msg.linear.x = 0.5 * sqrt(pow(transform.getOrigin().x(), 2) +
39  pow(transform.getOrigin().y(), 2));
40  turtle_vel.publish(vel_msg);
41 
42  rate.sleep();
43  }
44  return 0;
45 };
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)
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
bool sleep()
bool ok() const
#define ROS_ERROR(...)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


turtle_tf
Author(s): James Bowman, Isaac Saito
autogenerated on Wed Jun 5 2019 20:50:39