Go to the documentation of this file.
2 #include <turtlesim/Pose.h>
8 #include <geometry_msgs/Twist.h>
9 #include <turtle_actionlib/ShapeAction.h>
61 void controlCB(
const turtlesim::Pose::ConstPtr& msg)
72 double error_tol = 0.00001;
135 int main(
int argc,
char** argv)
turtle_actionlib::ShapeResult result_
ShapeAction(std::string name)
def normalize_angle_positive(angle)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void controlCB(const turtlesim::Pose::ConstPtr &msg)
actionlib::SimpleActionServer< turtle_actionlib::ShapeAction > as_
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Publisher advertise(AdvertiseOptions &ops)
void registerPreemptCallback(boost::function< void()> cb)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
void registerGoalCallback(boost::function< void()> cb)
const ROSCPP_DECL std::string & getName()
boost::shared_ptr< const Goal > acceptNewGoal()
geometry_msgs::Twist command_
turtle_actionlib
Author(s): Melonee Wise
autogenerated on Wed Mar 2 2022 00:05:51