$search
00001 #include <ros/ros.h> 00002 #include <turtlesim/Pose.h> 00003 #include <turtlesim/Velocity.h> 00004 00005 class Mimic 00006 { 00007 public: 00008 Mimic(); 00009 00010 private: 00011 void poseCallback(const turtlesim::PoseConstPtr& pose); 00012 00013 ros::Publisher vel_pub_; 00014 ros::Subscriber pose_sub_; 00015 }; 00016 00017 Mimic::Mimic() 00018 { 00019 ros::NodeHandle input_nh("input"); 00020 ros::NodeHandle output_nh("output"); 00021 vel_pub_ = output_nh.advertise<turtlesim::Velocity>("command_velocity", 1); 00022 pose_sub_ = input_nh.subscribe<turtlesim::Pose>("pose", 1, &Mimic::poseCallback, this); 00023 } 00024 00025 void Mimic::poseCallback(const turtlesim::PoseConstPtr& pose) 00026 { 00027 turtlesim::Velocity vel; 00028 vel.angular = pose->angular_velocity; 00029 vel.linear = pose->linear_velocity; 00030 vel_pub_.publish(vel); 00031 } 00032 00033 int main(int argc, char** argv) 00034 { 00035 ros::init(argc, argv, "turtle_mimic"); 00036 Mimic mimic; 00037 00038 ros::spin(); 00039 } 00040