1 #include <boost/bind.hpp> 3 #include <turtlesim/Pose.h> 4 #include <geometry_msgs/Twist.h> 5 #include <std_srvs/Empty.h> 36 return g_pose->angular_velocity < 0.0001 &&
g_pose->linear_velocity < 0.0001;
46 geometry_msgs::Twist twist;
47 twist.linear.x = linear;
48 twist.angular.z = angular;
148 int main(
int argc,
char** argv)
157 std_srvs::Empty empty;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
void stopForward(ros::Publisher twist_pub)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void turn(ros::Publisher twist_pub)
void poseCallback(const turtlesim::PoseConstPtr &pose)
void stopTurn(ros::Publisher twist_pub)
void forward(ros::Publisher twist_pub)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void commandTurtle(ros::Publisher twist_pub, float linear, float angular)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
turtlesim::PoseConstPtr g_pose
void timerCallback(const ros::TimerEvent &, ros::Publisher twist_pub)