3 #include <geometry_msgs/Twist.h> 4 #include <turtlesim/Spawn.h> 6 int main(
int argc,
char** argv){
18 node.
advertise<geometry_msgs::Twist>(
"turtle2/cmd_vel", 10);
26 listener.lookupTransform(
"/turtle2",
"/turtle1",
35 geometry_msgs::Twist vel_msg;
36 vel_msg.angular.z = 4.0 * atan2(transform.
getOrigin().
y(),
38 vel_msg.linear.x = 0.5 * sqrt(pow(transform.
getOrigin().
x(), 2) +
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
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)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)