Go to the documentation of this file.
3 #include <nav2d_navigator/MoveToPosition2DAction.h>
4 #include <geometry_msgs/PoseStamped.h>
13 void receiveGoal(
const geometry_msgs::PoseStamped::ConstPtr& msg)
15 nav2d_navigator::MoveToPosition2DGoal goal;
16 goal.target_pose.x = msg->pose.position.x;
17 goal.target_pose.y = msg->pose.position.y;
18 goal.target_pose.theta =
tf::getYaw(msg->pose.orientation);
19 goal.target_distance = 0.25;
20 goal.target_angle = 0.1;
25 int main(
int argc,
char **argv)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
static double getYaw(const geometry_msgs::Quaternion &msg_q)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
int main(int argc, char **argv)
void receiveGoal(const geometry_msgs::PoseStamped::ConstPtr &msg)
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())
actionlib::SimpleActionClient< nav2d_navigator::MoveToPosition2DAction > MoveClient
nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:37